aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp260
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.hpp46
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp33
-rw-r--r--src/modules/att_pos_estimator_ekf/module.mk3
-rw-r--r--src/modules/att_pos_estimator_ekf/params.c41
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp54
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c52
-rw-r--r--src/modules/attitude_estimator_so3/README3
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp678
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_params.c86
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_params.h67
-rw-r--r--src/modules/attitude_estimator_so3/module.mk8
-rw-r--r--src/modules/commander/accelerometer_calibration.c414
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp566
-rw-r--r--src/modules/commander/accelerometer_calibration.h46
-rw-r--r--src/modules/commander/airspeed_calibration.cpp154
-rw-r--r--src/modules/commander/airspeed_calibration.h46
-rw-r--r--src/modules/commander/baro_calibration.cpp60
-rw-r--r--src/modules/commander/baro_calibration.h (renamed from src/modules/mathlib/math/generic/Matrix.cpp)16
-rw-r--r--src/modules/commander/calibration_messages.h57
-rw-r--r--src/modules/commander/calibration_routines.cpp (renamed from src/modules/commander/calibration_routines.c)3
-rw-r--r--src/modules/commander/commander.c2078
-rw-r--r--src/modules/commander/commander.cpp1918
-rw-r--r--src/modules/commander/commander_helper.cpp306
-rw-r--r--src/modules/commander/commander_helper.h90
-rw-r--r--src/modules/commander/commander_params.c (renamed from src/modules/commander/commander.h)34
-rw-r--r--src/modules/commander/commander_tests/commander_tests.cpp (renamed from src/modules/mathlib/math/Vector.hpp)32
-rw-r--r--src/modules/commander/commander_tests/module.mk (renamed from src/modules/mathlib/CMSIS/library.mk)15
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp247
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.h44
-rw-r--r--src/modules/commander/gyro_calibration.cpp305
-rw-r--r--src/modules/commander/gyro_calibration.h (renamed from src/modules/mathlib/math/arm/Matrix.cpp)16
-rw-r--r--src/modules/commander/mag_calibration.cpp285
-rw-r--r--src/modules/commander/mag_calibration.h (renamed from src/modules/mathlib/math/generic/Vector.cpp)16
-rw-r--r--src/modules/commander/module.mk16
-rw-r--r--src/modules/commander/px4_custom_mode.h37
-rw-r--r--src/modules/commander/rc_calibration.cpp (renamed from src/modules/mathlib/math/Vector.cpp)98
-rw-r--r--src/modules/commander/rc_calibration.h (renamed from src/modules/mathlib/math/arm/Vector.cpp)16
-rw-r--r--src/modules/commander/state_machine_helper.c757
-rw-r--r--src/modules/commander/state_machine_helper.cpp738
-rw-r--r--src/modules/commander/state_machine_helper.h168
-rw-r--r--src/modules/controllib/block/Block.cpp4
-rw-r--r--src/modules/controllib/block/BlockParam.hpp29
-rw-r--r--src/modules/controllib/blocks.hpp37
-rw-r--r--src/modules/controllib/module.mk8
-rw-r--r--src/modules/controllib/uorb/UOrbPublication.cpp (renamed from src/modules/controllib/block/UOrbPublication.cpp)0
-rw-r--r--src/modules/controllib/uorb/UOrbPublication.hpp (renamed from src/modules/controllib/block/UOrbPublication.hpp)16
-rw-r--r--src/modules/controllib/uorb/UOrbSubscription.cpp (renamed from src/modules/controllib/block/UOrbSubscription.cpp)0
-rw-r--r--src/modules/controllib/uorb/UOrbSubscription.hpp (renamed from src/modules/controllib/block/UOrbSubscription.hpp)4
-rw-r--r--src/modules/controllib/uorb/blocks.cpp101
-rw-r--r--src/modules/controllib/uorb/blocks.hpp113
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.c4
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_main.c57
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.c6
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp (renamed from src/modules/controllib/fixedwing.cpp)220
-rw-r--r--src/modules/fixedwing_backside/fixedwing.hpp (renamed from src/modules/controllib/fixedwing.hpp)84
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp21
-rw-r--r--src/modules/fixedwing_backside/module.mk1
-rw-r--r--src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c8
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp782
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c136
-rw-r--r--src/modules/fw_att_control/module.mk41
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp1217
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c166
-rw-r--r--src/modules/fw_pos_control_l1/module.mk41
-rw-r--r--src/modules/gpio_led/gpio_led.c158
-rw-r--r--src/modules/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h264
-rw-r--r--src/modules/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h265
-rw-r--r--src/modules/mathlib/CMSIS/Include/arm_common_tables.h93
-rw-r--r--src/modules/mathlib/CMSIS/Include/arm_const_structs.h85
-rw-r--r--src/modules/mathlib/CMSIS/Include/arm_math.h7318
-rw-r--r--src/modules/mathlib/CMSIS/Include/core_cm3.h1627
-rw-r--r--src/modules/mathlib/CMSIS/Include/core_cm4.h1772
-rw-r--r--src/modules/mathlib/CMSIS/Include/core_cm4_simd.h673
-rw-r--r--src/modules/mathlib/CMSIS/Include/core_cmFunc.h636
-rw-r--r--src/modules/mathlib/CMSIS/Include/core_cmInstr.h688
-rw-r--r--src/modules/mathlib/CMSIS/libarm_cortexM3l_math.abin3039508 -> 0 bytes
-rwxr-xr-xsrc/modules/mathlib/CMSIS/libarm_cortexM4l_math.abin3049684 -> 0 bytes
-rwxr-xr-xsrc/modules/mathlib/CMSIS/libarm_cortexM4lf_math.abin2989192 -> 0 bytes
-rw-r--r--src/modules/mathlib/CMSIS/license.txt27
-rw-r--r--src/modules/mathlib/math/Dcm.cpp165
-rw-r--r--src/modules/mathlib/math/EulerAngles.cpp126
-rw-r--r--src/modules/mathlib/math/Matrix.cpp193
-rw-r--r--src/modules/mathlib/math/Quaternion.cpp174
-rw-r--r--src/modules/mathlib/math/arm/Matrix.hpp292
-rw-r--r--src/modules/mathlib/math/arm/Vector.hpp220
-rw-r--r--src/modules/mathlib/math/generic/Matrix.hpp437
-rw-r--r--src/modules/mathlib/math/generic/Vector.hpp227
-rw-r--r--src/modules/mathlib/math/nasa_rotation_def.pdfbin709235 -> 0 bytes
-rw-r--r--src/modules/mathlib/math/test_math.sce63
-rw-r--r--src/modules/mavlink/mavlink.c261
-rw-r--r--src/modules/mavlink/mavlink_bridge_header.h8
-rw-r--r--src/modules/mavlink/mavlink_hil.h9
-rw-r--r--src/modules/mavlink/mavlink_parameters.c1
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp (renamed from src/modules/mavlink/mavlink_receiver.c)475
-rw-r--r--src/modules/mavlink/missionlib.c200
-rw-r--r--src/modules/mavlink/missionlib.h2
-rw-r--r--src/modules/mavlink/module.mk3
-rw-r--r--src/modules/mavlink/orb_listener.c228
-rw-r--r--src/modules/mavlink/orb_topics.h16
-rw-r--r--src/modules/mavlink/util.h2
-rw-r--r--src/modules/mavlink/waypoints.c380
-rw-r--r--src/modules/mavlink/waypoints.h13
-rw-r--r--src/modules/mavlink_onboard/mavlink.c149
-rw-r--r--src/modules/mavlink_onboard/mavlink_bridge_header.h2
-rw-r--r--src/modules/mavlink_onboard/mavlink_receiver.c97
-rw-r--r--src/modules/mavlink_onboard/orb_topics.h4
-rw-r--r--src/modules/mavlink_onboard/util.h3
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c468
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c49
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.h24
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.c100
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.h26
-rw-r--r--src/modules/multirotor_pos_control/module.mk3
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c626
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c74
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.h59
-rw-r--r--src/modules/multirotor_pos_control/position_control.c235
-rw-r--r--src/modules/multirotor_pos_control/thrust_pid.c189
-rw-r--r--src/modules/multirotor_pos_control/thrust_pid.h (renamed from src/modules/mathlib/math/Quaternion.hpp)105
-rw-r--r--src/modules/navigator/module.mk41
-rw-r--r--src/modules/navigator/navigator_main.cpp604
-rw-r--r--src/modules/navigator/navigator_params.c (renamed from src/modules/mathlib/mathlib.h)28
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.c31
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.h13
-rw-r--r--src/modules/position_estimator_inav/module.mk41
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c652
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c96
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h87
-rwxr-xr-xsrc/modules/position_estimator_mc/position_estimator_mc_main.c7
-rw-r--r--src/modules/px4iofirmware/adc.c53
-rw-r--r--src/modules/px4iofirmware/controls.c288
-rw-r--r--src/modules/px4iofirmware/dsm.c421
-rw-r--r--src/modules/px4iofirmware/i2c.c11
-rw-r--r--src/modules/px4iofirmware/mixer.cpp238
-rw-r--r--src/modules/px4iofirmware/module.mk12
-rw-r--r--src/modules/px4iofirmware/protocol.h217
-rw-r--r--src/modules/px4iofirmware/px4io.c135
-rw-r--r--src/modules/px4iofirmware/px4io.h105
-rw-r--r--src/modules/px4iofirmware/registers.c365
-rw-r--r--src/modules/px4iofirmware/safety.c35
-rw-r--r--src/modules/px4iofirmware/sbus.c95
-rw-r--r--src/modules/px4iofirmware/serial.c338
-rw-r--r--src/modules/sdlog2/logbuffer.c133
-rw-r--r--src/modules/sdlog2/logbuffer.h (renamed from src/modules/mathlib/math/EulerAngles.hpp)52
-rw-r--r--src/modules/sdlog2/module.mk43
-rw-r--r--src/modules/sdlog2/sdlog2.c1463
-rw-r--r--src/modules/sdlog2/sdlog2_format.h98
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h311
-rw-r--r--src/modules/segway/BlockSegwayController.cpp58
-rw-r--r--src/modules/segway/BlockSegwayController.hpp27
-rw-r--r--src/modules/segway/module.mk (renamed from src/modules/mathlib/module.mk)28
-rw-r--r--src/modules/segway/params.c8
-rw-r--r--src/modules/segway/segway_main.cpp157
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensor_params.c350
-rw-r--r--src/modules/sensors/sensors.cpp687
-rw-r--r--src/modules/systemlib/airspeed.c22
-rw-r--r--src/modules/systemlib/airspeed.h8
-rw-r--r--src/modules/systemlib/board_serial.c (renamed from src/modules/multirotor_pos_control/position_control.h)36
-rw-r--r--src/modules/systemlib/board_serial.h49
-rw-r--r--src/modules/systemlib/bson/tinybson.c3
-rw-r--r--src/modules/systemlib/conversions.c97
-rw-r--r--src/modules/systemlib/conversions.h33
-rw-r--r--src/modules/systemlib/cpuload.c41
-rw-r--r--src/modules/systemlib/cpuload.h12
-rw-r--r--src/modules/systemlib/geo/geo.c439
-rw-r--r--src/modules/systemlib/geo/geo.h97
-rw-r--r--src/modules/systemlib/hx_stream.c185
-rw-r--r--src/modules/systemlib/hx_stream.h42
-rw-r--r--src/modules/systemlib/mavlink_log.c (renamed from src/modules/mavlink/mavlink_log.c)24
-rw-r--r--src/modules/systemlib/mixer/mixer.cpp45
-rw-r--r--src/modules/systemlib/mixer/mixer.h26
-rw-r--r--src/modules/systemlib/mixer/mixer_group.cpp15
-rw-r--r--src/modules/systemlib/mixer/mixer_load.c (renamed from src/modules/mathlib/math/test/test.cpp)98
-rw-r--r--src/modules/systemlib/mixer/mixer_load.h (renamed from src/modules/mathlib/math/test/test.hpp)23
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp46
-rw-r--r--src/modules/systemlib/mixer/mixer_simple.cpp68
-rw-r--r--src/modules/systemlib/mixer/module.mk3
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables13
-rw-r--r--src/modules/systemlib/module.mk10
-rw-r--r--src/modules/systemlib/otp.c224
-rw-r--r--src/modules/systemlib/otp.h151
-rw-r--r--src/modules/systemlib/param/param.c102
-rw-r--r--src/modules/systemlib/perf_counter.c70
-rw-r--r--src/modules/systemlib/perf_counter.h22
-rw-r--r--src/modules/systemlib/pid/pid.c93
-rw-r--r--src/modules/systemlib/pid/pid.h30
-rw-r--r--src/modules/systemlib/ppm_decode.h1
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c151
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.h (renamed from src/modules/mathlib/math/Dcm.hpp)90
-rw-r--r--src/modules/systemlib/rc_check.c151
-rw-r--r--src/modules/systemlib/rc_check.h52
-rw-r--r--src/modules/systemlib/system_params.c47
-rw-r--r--src/modules/systemlib/systemlib.c18
-rw-r--r--src/modules/systemlib/systemlib.h6
-rw-r--r--src/modules/test/foo.c4
-rw-r--r--src/modules/test/module.mk4
-rw-r--r--src/modules/uORB/objects_common.cpp48
-rw-r--r--src/modules/uORB/topics/actuator_armed.h58
-rw-r--r--src/modules/uORB/topics/actuator_controls.h26
-rw-r--r--src/modules/uORB/topics/actuator_controls_effective.h51
-rw-r--r--src/modules/uORB/topics/actuator_outputs.h11
-rw-r--r--src/modules/uORB/topics/battery_status.h9
-rw-r--r--src/modules/uORB/topics/debug_key_value.h1
-rw-r--r--src/modules/uORB/topics/differential_pressure.h10
-rw-r--r--src/modules/uORB/topics/esc_status.h116
-rw-r--r--src/modules/uORB/topics/filtered_bottom_flow.h (renamed from src/modules/mathlib/math/Vector3.cpp)85
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h13
-rw-r--r--src/modules/uORB/topics/mission.h99
-rw-r--r--src/modules/uORB/topics/navigation_capabilities.h65
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h10
-rw-r--r--src/modules/uORB/topics/omnidirectional_flow.h1
-rw-r--r--src/modules/uORB/topics/optical_flow.h4
-rw-r--r--src/modules/uORB/topics/parameter_update.h9
-rw-r--r--src/modules/uORB/topics/rc_channels.h49
-rw-r--r--src/modules/uORB/topics/safety.h (renamed from src/modules/mathlib/math/Matrix.hpp)40
-rw-r--r--src/modules/uORB/topics/sensor_combined.h10
-rw-r--r--src/modules/uORB/topics/servorail_status.h67
-rw-r--r--src/modules/uORB/topics/subsystem_info.h8
-rw-r--r--src/modules/uORB/topics/telemetry_status.h76
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h1
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h8
-rw-r--r--src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h69
-rw-r--r--src/modules/uORB/topics/vehicle_command.h14
-rw-r--r--src/modules/uORB/topics/vehicle_control_debug.h87
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h93
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h21
-rw-r--r--src/modules/uORB/topics/vehicle_global_position_set_triplet.h4
-rw-r--r--src/modules/uORB/topics/vehicle_global_position_setpoint.h10
-rw-r--r--src/modules/uORB/topics/vehicle_global_velocity_setpoint.h (renamed from src/modules/mathlib/math/Vector3.hpp)51
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h6
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h42
-rw-r--r--src/modules/uORB/topics/vehicle_status.h174
-rw-r--r--src/modules/uORB/uORB.cpp4
-rw-r--r--src/modules/unit_test/module.mk39
-rw-r--r--src/modules/unit_test/unit_test.cpp65
-rw-r--r--src/modules/unit_test/unit_test.h93
238 files changed, 20870 insertions, 23077 deletions
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
index 4ef150da1..ecca04dd7 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -34,12 +34,14 @@
/**
* @file KalmanNav.cpp
*
- * kalman filter navigation code
+ * Kalman filter navigation code
*/
#include <poll.h>
#include "KalmanNav.hpp"
+#include <systemlib/err.h>
+#include <geo/geo.h>
// constants
// Titterton pg. 52
@@ -58,8 +60,8 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
P0(9, 9),
V(6, 6),
// attitude measurement ekf matrices
- HAtt(6, 9),
- RAtt(6, 6),
+ HAtt(4, 9),
+ RAtt(4, 4),
// position measurement ekf matrices
HPos(6, 9),
RPos(6, 6),
@@ -72,6 +74,7 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
_param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
// publications
_pos(&getPublications(), ORB_ID(vehicle_global_position)),
+ _localPos(&getPublications(), ORB_ID(vehicle_local_position)),
_att(&getPublications(), ORB_ID(vehicle_attitude)),
// timestamps
_pubTimeStamp(hrt_absolute_time()),
@@ -88,6 +91,7 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
phi(0), theta(0), psi(0),
vN(0), vE(0), vD(0),
lat(0), lon(0), alt(0),
+ lat0(0), lon0(0), alt0(0),
// parameters for ground station
_vGyro(this, "V_GYRO"),
_vAccel(this, "V_ACCEL"),
@@ -123,8 +127,15 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
lon = 0.0f;
alt = 0.0f;
- // initialize quaternions
- q = Quaternion(EulerAngles(phi, theta, psi));
+ // initialize rotation quaternion with a single raw sensor measurement
+ _sensors.update();
+ q = init(
+ _sensors.accelerometer_m_s2[0],
+ _sensors.accelerometer_m_s2[1],
+ _sensors.accelerometer_m_s2[2],
+ _sensors.magnetometer_ga[0],
+ _sensors.magnetometer_ga[1],
+ _sensors.magnetometer_ga[2]);
// initialize dcm
C_nb = Dcm(q);
@@ -141,6 +152,45 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
updateParams();
}
+math::Quaternion KalmanNav::init(float ax, float ay, float az, float mx, float my, float mz)
+{
+ float initialRoll, initialPitch;
+ float cosRoll, sinRoll, cosPitch, sinPitch;
+ float magX, magY;
+ float initialHdg, cosHeading, sinHeading;
+
+ initialRoll = atan2(-ay, -az);
+ initialPitch = atan2(ax, -az);
+
+ cosRoll = cosf(initialRoll);
+ sinRoll = sinf(initialRoll);
+ cosPitch = cosf(initialPitch);
+ sinPitch = sinf(initialPitch);
+
+ magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
+
+ magY = my * cosRoll - mz * sinRoll;
+
+ initialHdg = atan2f(-magY, magX);
+
+ cosRoll = cosf(initialRoll * 0.5f);
+ sinRoll = sinf(initialRoll * 0.5f);
+
+ cosPitch = cosf(initialPitch * 0.5f);
+ sinPitch = sinf(initialPitch * 0.5f);
+
+ cosHeading = cosf(initialHdg * 0.5f);
+ sinHeading = sinf(initialHdg * 0.5f);
+
+ float q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
+ float q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
+ float q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
+ float q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
+
+ return math::Quaternion(q0, q1, q2, q3);
+
+}
+
void KalmanNav::update()
{
using namespace math;
@@ -174,15 +224,12 @@ void KalmanNav::update()
updateSubscriptions();
// initialize attitude when sensors online
- if (!_attitudeInitialized && sensorsUpdate &&
- _sensors.accelerometer_counter > 10 &&
- _sensors.gyro_counter > 10 &&
- _sensors.magnetometer_counter > 10) {
+ if (!_attitudeInitialized && sensorsUpdate) {
if (correctAtt() == ret_ok) _attitudeInitCounter++;
if (_attitudeInitCounter > 100) {
- printf("[kalman_demo] initialized EKF attitude\n");
- printf("phi: %8.4f, theta: %8.4f, psi: %8.4f\n",
+ warnx("initialized EKF attitude\n");
+ warnx("phi: %8.4f, theta: %8.4f, psi: %8.4f\n",
double(phi), double(theta), double(psi));
_attitudeInitialized = true;
}
@@ -201,14 +248,24 @@ void KalmanNav::update()
setLatDegE7(_gps.lat);
setLonDegE7(_gps.lon);
setAltE3(_gps.alt);
+ // set reference position for
+ // local position
+ lat0 = lat;
+ lon0 = lon;
+ alt0 = alt;
+ // XXX map_projection has internal global
+ // states that multiple things could change,
+ // should make map_projection take reference
+ // lat/lon and not have init
+ map_projection_init(lat0, lon0);
_positionInitialized = true;
- printf("[kalman_demo] initialized EKF state with GPS\n");
- printf("vN: %8.4f, vE: %8.4f, vD: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
+ warnx("initialized EKF state with GPS\n");
+ warnx("vN: %8.4f, vE: %8.4f, vD: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
double(vN), double(vE), double(vD),
- lat, lon, alt);
+ lat, lon, double(alt));
}
- // prediciton step
+ // prediction step
// using sensors timestamp so we can account for packet lag
float dt = (_sensors.timestamp - _predictTimeStamp) / 1.0e6f;
//printf("dt: %15.10f\n", double(dt));
@@ -233,7 +290,7 @@ void KalmanNav::update()
// attitude correction step
if (_attitudeInitialized // initialized
&& sensorsUpdate // new data
- && _sensors.timestamp - _attTimeStamp > 1e6 / 20 // 20 Hz
+ && _sensors.timestamp - _attTimeStamp > 1e6 / 50 // 50 Hz
) {
_attTimeStamp = _sensors.timestamp;
correctAtt();
@@ -260,7 +317,7 @@ void KalmanNav::updatePublications()
{
using namespace math;
- // position publication
+ // global position publication
_pos.timestamp = _pubTimeStamp;
_pos.time_gps_usec = _gps.timestamp_position;
_pos.valid = true;
@@ -271,7 +328,32 @@ void KalmanNav::updatePublications()
_pos.vx = vN;
_pos.vy = vE;
_pos.vz = vD;
- _pos.hdg = psi;
+ _pos.yaw = psi;
+
+ // local position publication
+ float x;
+ float y;
+ bool landed = alt < (alt0 + 0.1); // XXX improve?
+ map_projection_project(lat, lon, &x, &y);
+ _localPos.timestamp = _pubTimeStamp;
+ _localPos.xy_valid = true;
+ _localPos.z_valid = true;
+ _localPos.v_xy_valid = true;
+ _localPos.v_z_valid = true;
+ _localPos.x = x;
+ _localPos.y = y;
+ _localPos.z = alt0 - alt;
+ _localPos.vx = vN;
+ _localPos.vy = vE;
+ _localPos.vz = vD;
+ _localPos.yaw = psi;
+ _localPos.xy_global = true;
+ _localPos.z_global = true;
+ _localPos.ref_timestamp = _pubTimeStamp;
+ _localPos.ref_lat = getLatDegE7();
+ _localPos.ref_lon = getLonDegE7();
+ _localPos.ref_alt = 0;
+ _localPos.landed = landed;
// attitude publication
_att.timestamp = _pubTimeStamp;
@@ -296,8 +378,10 @@ void KalmanNav::updatePublications()
// selectively update publications,
// do NOT call superblock do-all method
- if (_positionInitialized)
+ if (_positionInitialized) {
_pos.update();
+ _localPos.update();
+ }
if (_attitudeInitialized)
_att.update();
@@ -480,26 +564,32 @@ int KalmanNav::correctAtt()
// trig
float cosPhi = cosf(phi);
float cosTheta = cosf(theta);
- float cosPsi = cosf(psi);
+ // float cosPsi = cosf(psi);
float sinPhi = sinf(phi);
float sinTheta = sinf(theta);
- float sinPsi = sinf(psi);
-
- // mag measurement
- Vector3 zMag(_sensors.magnetometer_ga);
- //float magNorm = zMag.norm();
- zMag = zMag.unit();
+ // float sinPsi = sinf(psi);
// mag predicted measurement
// choosing some typical magnetic field properties,
// TODO dip/dec depend on lat/ lon/ time
- float dip = _magDip.get() / M_RAD_TO_DEG_F; // dip, inclination with level
+ //float dip = _magDip.get() / M_RAD_TO_DEG_F; // dip, inclination with level
float dec = _magDec.get() / M_RAD_TO_DEG_F; // declination, clockwise rotation from north
- float bN = cosf(dip) * cosf(dec);
- float bE = cosf(dip) * sinf(dec);
- float bD = sinf(dip);
- Vector3 bNav(bN, bE, bD);
- Vector3 zMagHat = (C_nb.transpose() * bNav).unit();
+
+ // compensate roll and pitch, but not yaw
+ // XXX take the vectors out of the C_nb matrix to avoid singularities
+ math::Dcm C_rp(math::EulerAngles(phi, theta, 0.0f));//C_nb.transpose();
+
+ // mag measurement
+ Vector3 magBody(_sensors.magnetometer_ga);
+
+ // transform to earth frame
+ Vector3 magNav = C_rp * magBody;
+
+ // calculate error between estimate and measurement
+ // apply declination correction for true heading as well.
+ float yMag = -atan2f(magNav(1),magNav(0)) - psi - dec;
+ if (yMag > M_PI_F) yMag -= 2*M_PI_F;
+ if (yMag < -M_PI_F) yMag += 2*M_PI_F;
// accel measurement
Vector3 zAccel(_sensors.accelerometer_m_s2);
@@ -512,9 +602,9 @@ int KalmanNav::correctAtt()
bool ignoreAccel = fabsf(accelMag - _g.get()) > 1.1f;
if (ignoreAccel) {
+ RAttAdjust(1, 1) = 1.0e10;
+ RAttAdjust(2, 2) = 1.0e10;
RAttAdjust(3, 3) = 1.0e10;
- RAttAdjust(4, 4) = 1.0e10;
- RAttAdjust(5, 5) = 1.0e10;
} else {
//printf("correcting attitude with accel\n");
@@ -523,58 +613,25 @@ int KalmanNav::correctAtt()
// accel predicted measurement
Vector3 zAccelHat = (C_nb.transpose() * Vector3(0, 0, -_g.get())).unit();
- // combined measurement
- Vector zAtt(6);
- Vector zAttHat(6);
+ // calculate residual
+ Vector y(4);
+ y(0) = yMag;
+ y(1) = zAccel(0) - zAccelHat(0);
+ y(2) = zAccel(1) - zAccelHat(1);
+ y(3) = zAccel(2) - zAccelHat(2);
- for (int i = 0; i < 3; i++) {
- zAtt(i) = zMag(i);
- zAtt(i + 3) = zAccel(i);
- zAttHat(i) = zMagHat(i);
- zAttHat(i + 3) = zAccelHat(i);
- }
+ // HMag
+ HAtt(0, 2) = 1;
- // HMag , HAtt (0-2,:)
- float tmp1 =
- cosPsi * cosTheta * bN +
- sinPsi * cosTheta * bE -
- sinTheta * bD;
- HAtt(0, 1) = -(
- cosPsi * sinTheta * bN +
- sinPsi * sinTheta * bE +
- cosTheta * bD
- );
- HAtt(0, 2) = -cosTheta * (sinPsi * bN - cosPsi * bE);
- HAtt(1, 0) =
- (cosPhi * cosPsi * sinTheta + sinPhi * sinPsi) * bN +
- (cosPhi * sinPsi * sinTheta - sinPhi * cosPsi) * bE +
- cosPhi * cosTheta * bD;
- HAtt(1, 1) = sinPhi * tmp1;
- HAtt(1, 2) = -(
- (sinPhi * sinPsi * sinTheta + cosPhi * cosPsi) * bN -
- (sinPhi * cosPsi * sinTheta - cosPhi * sinPsi) * bE
- );
- HAtt(2, 0) = -(
- (sinPhi * cosPsi * sinTheta - cosPhi * sinPsi) * bN +
- (sinPhi * sinPsi * sinTheta + cosPhi * cosPsi) * bE +
- (sinPhi * cosTheta) * bD
- );
- HAtt(2, 1) = cosPhi * tmp1;
- HAtt(2, 2) = -(
- (cosPhi * sinPsi * sinTheta - sinPhi * cosTheta) * bN -
- (cosPhi * cosPsi * sinTheta + sinPhi * sinPsi) * bE
- );
-
- // HAccel , HAtt (3-5,:)
- HAtt(3, 1) = cosTheta;
- HAtt(4, 0) = -cosPhi * cosTheta;
- HAtt(4, 1) = sinPhi * sinTheta;
- HAtt(5, 0) = sinPhi * cosTheta;
- HAtt(5, 1) = cosPhi * sinTheta;
+ // HAccel
+ HAtt(1, 1) = cosTheta;
+ HAtt(2, 0) = -cosPhi * cosTheta;
+ HAtt(2, 1) = sinPhi * sinTheta;
+ HAtt(3, 0) = sinPhi * cosTheta;
+ HAtt(3, 1) = cosPhi * sinTheta;
// compute correction
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
- Vector y = zAtt - zAttHat; // residual
Matrix S = HAtt * P * HAtt.transpose() + RAttAdjust; // residual covariance
Matrix K = P * HAtt.transpose() * S.inverse();
Vector xCorrect = K * y;
@@ -585,7 +642,7 @@ int KalmanNav::correctAtt()
if (isnan(val) || isinf(val)) {
// abort correction and return
- printf("[kalman_demo] numerical failure in att correction\n");
+ warnx("numerical failure in att correction\n");
// reset P matrix to P0
P = P0;
return ret_error;
@@ -615,11 +672,8 @@ int KalmanNav::correctAtt()
float beta = y.dot(S.inverse() * y);
if (beta > _faultAtt.get()) {
- printf("fault in attitude: beta = %8.4f\n", (double)beta);
- printf("y:\n"); y.print();
- printf("zMagHat:\n"); zMagHat.print();
- printf("zMag:\n"); zMag.print();
- printf("bNav:\n"); bNav.print();
+ warnx("fault in attitude: beta = %8.4f", (double)beta);
+ warnx("y:"); y.print();
}
// update quaternions from euler
@@ -637,10 +691,10 @@ int KalmanNav::correctPos()
Vector y(6);
y(0) = _gps.vel_n_m_s - vN;
y(1) = _gps.vel_e_m_s - vE;
- y(2) = double(_gps.lat) - lat * 1.0e7 * M_RAD_TO_DEG;
- y(3) = double(_gps.lon) - lon * 1.0e7 * M_RAD_TO_DEG;
- y(4) = double(_gps.alt) / 1.0e3 - alt;
- y(5) = double(_sensors.baro_alt_meter) - alt;
+ y(2) = double(_gps.lat) - double(lat) * 1.0e7 * M_RAD_TO_DEG;
+ y(3) = double(_gps.lon) - double(lon) * 1.0e7 * M_RAD_TO_DEG;
+ y(4) = _gps.alt / 1.0e3f - alt;
+ y(5) = _sensors.baro_alt_meter - alt;
// compute correction
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
@@ -652,9 +706,9 @@ int KalmanNav::correctPos()
for (size_t i = 0; i < xCorrect.getRows(); i++) {
float val = xCorrect(i);
- if (isnan(val) || isinf(val)) {
+ if (!isfinite(val)) {
// abort correction and return
- printf("[kalman_demo] numerical failure in gps correction\n");
+ warnx("numerical failure in gps correction\n");
// fallback to GPS
vN = _gps.vel_n_m_s;
vE = _gps.vel_e_m_s;
@@ -674,7 +728,7 @@ int KalmanNav::correctPos()
vD += xCorrect(VD);
lat += double(xCorrect(LAT));
lon += double(xCorrect(LON));
- alt += double(xCorrect(ALT));
+ alt += xCorrect(ALT);
// update state covariance
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
@@ -683,9 +737,10 @@ int KalmanNav::correctPos()
// fault detetcion
float beta = y.dot(S.inverse() * y);
- if (beta > _faultPos.get()) {
- printf("fault in gps: beta = %8.4f\n", (double)beta);
- printf("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
+ static int counter = 0;
+ if (beta > _faultPos.get() && (counter % 10 == 0)) {
+ warnx("fault in gps: beta = %8.4f", (double)beta);
+ warnx("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f, baro: %8.4f",
double(y(0) / sqrtf(RPos(0, 0))),
double(y(1) / sqrtf(RPos(1, 1))),
double(y(2) / sqrtf(RPos(2, 2))),
@@ -693,6 +748,7 @@ int KalmanNav::correctPos()
double(y(4) / sqrtf(RPos(4, 4))),
double(y(5) / sqrtf(RPos(5, 5))));
}
+ counter++;
return ret_ok;
}
@@ -720,8 +776,6 @@ void KalmanNav::updateParams()
if (noiseMagSq < noiseMin) noiseMagSq = noiseMin;
RAtt(0, 0) = noiseMagSq; // normalized direction
- RAtt(1, 1) = noiseMagSq;
- RAtt(2, 2) = noiseMagSq;
// accelerometer noise
float noiseAccelSq = _rAccel.get() * _rAccel.get();
@@ -729,9 +783,9 @@ void KalmanNav::updateParams()
// bound noise to prevent singularities
if (noiseAccelSq < noiseMin) noiseAccelSq = noiseMin;
- RAtt(3, 3) = noiseAccelSq; // normalized direction
- RAtt(4, 4) = noiseAccelSq;
- RAtt(5, 5) = noiseAccelSq;
+ RAtt(1, 1) = noiseAccelSq; // normalized direction
+ RAtt(2, 2) = noiseAccelSq;
+ RAtt(3, 3) = noiseAccelSq;
// gps noise
float R = R0 + float(alt);
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
index c2bf18115..a69bde1a6 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -47,15 +47,20 @@
#include <mathlib/mathlib.h>
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
-#include <controllib/block/UOrbSubscription.hpp>
-#include <controllib/block/UOrbPublication.hpp>
+#include <controllib/uorb/UOrbSubscription.hpp>
+#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/parameter_update.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_gyro.h>
+#include <drivers/drv_mag.h>
+
#include <drivers/drv_hrt.h>
#include <poll.h>
#include <unistd.h>
@@ -78,6 +83,9 @@ public:
*/
virtual ~KalmanNav() {};
+
+ math::Quaternion init(float ax, float ay, float az, float mx, float my, float mz);
+
/**
* The main callback function for the class
*/
@@ -135,6 +143,7 @@ protected:
control::UOrbSubscription<parameter_update_s> _param_update; /**< parameter update sub. */
// publications
control::UOrbPublication<vehicle_global_position_s> _pos; /**< position pub. */
+ control::UOrbPublication<vehicle_local_position_s> _localPos; /**< local position pub. */
control::UOrbPublication<vehicle_attitude_s> _att; /**< attitude pub. */
// time stamps
uint64_t _pubTimeStamp; /**< output data publication time stamp */
@@ -151,21 +160,24 @@ protected:
enum {PHI = 0, THETA, PSI, VN, VE, VD, LAT, LON, ALT}; /**< state enumeration */
float phi, theta, psi; /**< 3-2-1 euler angles */
float vN, vE, vD; /**< navigation velocity, m/s */
- double lat, lon, alt; /**< lat, lon, alt, radians */
+ double lat, lon; /**< lat, lon radians */
// parameters
- control::BlockParam<float> _vGyro; /**< gyro process noise */
- control::BlockParam<float> _vAccel; /**< accelerometer process noise */
- control::BlockParam<float> _rMag; /**< magnetometer measurement noise */
- control::BlockParam<float> _rGpsVel; /**< gps velocity measurement noise */
- control::BlockParam<float> _rGpsPos; /**< gps position measurement noise */
- control::BlockParam<float> _rGpsAlt; /**< gps altitude measurement noise */
- control::BlockParam<float> _rPressAlt; /**< press altitude measurement noise */
- control::BlockParam<float> _rAccel; /**< accelerometer measurement noise */
- control::BlockParam<float> _magDip; /**< magnetic inclination with level */
- control::BlockParam<float> _magDec; /**< magnetic declination, clockwise rotation */
- control::BlockParam<float> _g; /**< gravitational constant */
- control::BlockParam<float> _faultPos; /**< fault detection threshold for position */
- control::BlockParam<float> _faultAtt; /**< fault detection threshold for attitude */
+ float alt; /**< altitude, meters */
+ double lat0, lon0; /**< reference latitude and longitude */
+ float alt0; /**< refeerence altitude (ground height) */
+ control::BlockParamFloat _vGyro; /**< gyro process noise */
+ control::BlockParamFloat _vAccel; /**< accelerometer process noise */
+ control::BlockParamFloat _rMag; /**< magnetometer measurement noise */
+ control::BlockParamFloat _rGpsVel; /**< gps velocity measurement noise */
+ control::BlockParamFloat _rGpsPos; /**< gps position measurement noise */
+ control::BlockParamFloat _rGpsAlt; /**< gps altitude measurement noise */
+ control::BlockParamFloat _rPressAlt; /**< press altitude measurement noise */
+ control::BlockParamFloat _rAccel; /**< accelerometer measurement noise */
+ control::BlockParamFloat _magDip; /**< magnetic inclination with level */
+ control::BlockParamFloat _magDec; /**< magnetic declination, clockwise rotation */
+ control::BlockParamFloat _g; /**< gravitational constant */
+ control::BlockParamFloat _faultPos; /**< fault detection threshold for position */
+ control::BlockParamFloat _faultAtt; /**< fault detection threshold for attitude */
// status
bool _attitudeInitialized;
bool _positionInitialized;
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 3b411031a..372b2d162 100644
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: James Goppert
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,8 +33,10 @@
****************************************************************************/
/**
- * @file kalman_demo.cpp
- * Demonstration of control library
+ * @file kalman_main.cpp
+ * Combined attitude / position estimator.
+ *
+ * @author James Goppert
*/
#include <nuttx/config.h>
@@ -44,13 +46,14 @@
#include <string.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
#include "KalmanNav.hpp"
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
+static int daemon_task; /**< Handle of deamon task / thread */
/**
* Deamon management function.
@@ -73,7 +76,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: kalman_demo {start|stop|status} [-p <additional params>]\n\n");
+ warnx("usage: att_pos_estimator_ekf {start|stop|status} [-p <additional params>]");
exit(1);
}
@@ -94,15 +97,16 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("kalman_demo already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn_cmd("kalman_demo",
+
+ daemon_task = task_spawn_cmd("att_pos_estimator_ekf",
SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
+ SCHED_PRIORITY_MAX - 30,
4096,
kalman_demo_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -116,13 +120,14 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tkalman_demo app is running\n");
+ warnx("is running\n");
+ exit(0);
} else {
- printf("\tkalman_demo app not started\n");
+ warnx("not started\n");
+ exit(1);
}
- exit(0);
}
usage("unrecognized command");
@@ -132,7 +137,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
int kalman_demo_thread_main(int argc, char *argv[])
{
- printf("[kalman_demo] starting\n");
+ warnx("starting");
using namespace math;
@@ -144,7 +149,7 @@ int kalman_demo_thread_main(int argc, char *argv[])
nav.update();
}
- printf("[kalman_demo] exiting.\n");
+ warnx("exiting.");
thread_running = false;
diff --git a/src/modules/att_pos_estimator_ekf/module.mk b/src/modules/att_pos_estimator_ekf/module.mk
index 21b7c9166..8d4a40d95 100644
--- a/src/modules/att_pos_estimator_ekf/module.mk
+++ b/src/modules/att_pos_estimator_ekf/module.mk
@@ -37,9 +37,6 @@
MODULE_COMMAND = att_pos_estimator_ekf
-# XXX this might be intended for the spawned deamon, validate
-MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
-
SRCS = kalman_main.cpp \
KalmanNav.cpp \
params.c
diff --git a/src/modules/att_pos_estimator_ekf/params.c b/src/modules/att_pos_estimator_ekf/params.c
index 50642f067..4af5edead 100644
--- a/src/modules/att_pos_estimator_ekf/params.c
+++ b/src/modules/att_pos_estimator_ekf/params.c
@@ -1,12 +1,45 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
#include <systemlib/param/param.h>
/*PARAM_DEFINE_FLOAT(NAME,0.0f);*/
PARAM_DEFINE_FLOAT(KF_V_GYRO, 0.008f);
PARAM_DEFINE_FLOAT(KF_V_ACCEL, 1.0f);
-PARAM_DEFINE_FLOAT(KF_R_MAG, 1.0f);
-PARAM_DEFINE_FLOAT(KF_R_GPS_VEL, 1.0f);
-PARAM_DEFINE_FLOAT(KF_R_GPS_POS, 5.0f);
-PARAM_DEFINE_FLOAT(KF_R_GPS_ALT, 5.0f);
+PARAM_DEFINE_FLOAT(KF_R_MAG, 0.8f);
+PARAM_DEFINE_FLOAT(KF_R_GPS_VEL, 0.5f);
+PARAM_DEFINE_FLOAT(KF_R_GPS_POS, 2.0f);
+PARAM_DEFINE_FLOAT(KF_R_GPS_ALT, 3.0f);
PARAM_DEFINE_FLOAT(KF_R_PRESS_ALT, 0.1f);
PARAM_DEFINE_FLOAT(KF_R_ACCEL, 1.0f);
PARAM_DEFINE_FLOAT(KF_FAULT_POS, 10.0f);
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 7e3eca085..a70a14fe4 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -57,7 +57,7 @@
#include <uORB/topics/debug_key_value.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <drivers/drv_hrt.h>
@@ -126,7 +126,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
attitude_estimator_ekf_task = task_spawn_cmd("attitude_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 12400,
+ 14000,
attitude_estimator_ekf_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
@@ -139,10 +139,12 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tattitude_estimator_ekf app is running\n");
+ warnx("running");
+ exit(0);
} else {
- printf("\tattitude_estimator_ekf app not started\n");
+ warnx("not started");
+ exit(1);
}
exit(0);
@@ -214,27 +216,26 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
memset(&raw, 0, sizeof(raw));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
- struct vehicle_status_s state;
- memset(&state, 0, sizeof(state));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
uint64_t last_data = 0;
uint64_t last_measurement = 0;
/* subscribe to raw data */
int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
- /* rate-limit raw data updates to 200Hz */
- orb_set_interval(sub_raw, 4);
+ /* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */
+ orb_set_interval(sub_raw, 3);
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
- /* subscribe to system state*/
- int sub_state = orb_subscribe(ORB_ID(vehicle_status));
+ /* subscribe to control mode*/
+ int sub_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
/* advertise attitude */
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
-
int loopcounter = 0;
int printcounter = 0;
@@ -281,9 +282,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* XXX this is seriously bad - should be an emergency */
} else if (ret == 0) {
/* check if we're in HIL - not getting sensor data is fine then */
- orb_copy(ORB_ID(vehicle_status), sub_state, &state);
+ orb_copy(ORB_ID(vehicle_control_mode), sub_control_mode, &control_mode);
- if (!state.flag_hil_enabled) {
+ if (!control_mode.flag_system_hil_enabled) {
fprintf(stderr,
"[att ekf] WARNING: Not getting sensors - sensor app running?\n");
}
@@ -307,18 +308,20 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_copy(ORB_ID(sensor_combined), sub_raw, &raw);
if (!initialized) {
+ // XXX disabling init for now
+ initialized = true;
- gyro_offsets[0] += raw.gyro_rad_s[0];
- gyro_offsets[1] += raw.gyro_rad_s[1];
- gyro_offsets[2] += raw.gyro_rad_s[2];
- offset_count++;
+ // gyro_offsets[0] += raw.gyro_rad_s[0];
+ // gyro_offsets[1] += raw.gyro_rad_s[1];
+ // gyro_offsets[2] += raw.gyro_rad_s[2];
+ // offset_count++;
- if (hrt_absolute_time() - start_time > 3000000LL) {
- initialized = true;
- gyro_offsets[0] /= offset_count;
- gyro_offsets[1] /= offset_count;
- gyro_offsets[2] /= offset_count;
- }
+ // if (hrt_absolute_time() - start_time > 3000000LL) {
+ // initialized = true;
+ // gyro_offsets[0] /= offset_count;
+ // gyro_offsets[1] /= offset_count;
+ // gyro_offsets[2] /= offset_count;
+ // }
} else {
@@ -382,7 +385,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
static bool const_initialized = false;
/* initialize with good values once we have a reasonable dt estimate */
- if (!const_initialized && dt < 0.05f && dt > 0.005f) {
+ if (!const_initialized && dt < 0.05f && dt > 0.001f) {
dt = 0.005f;
parameters_update(&ekf_param_handles, &ekf_params);
@@ -422,7 +425,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
+ if (last_data > 0 && raw.timestamp - last_data > 12000)
+ printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
last_data = raw.timestamp;
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
index 7d3812abd..3cfddf28e 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
@@ -44,42 +44,44 @@
/* Extended Kalman Filter covariances */
/* gyro process noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q0, 1e-4f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q1, 0.08f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q2, 0.009f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q0, 1e-4f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q1, 0.08f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q2, 0.009f);
/* gyro offsets process noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q3, 0.005f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_Q4, 0.0f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q3, 0.005f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q4, 0.0f);
/* gyro measurement noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R0, 0.0008f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R1, 0.8f);
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R2, 1.0f);
-/* accelerometer measurement noise */
-PARAM_DEFINE_FLOAT(EKF_ATT_V2_R3, 0.0f);
+PARAM_DEFINE_FLOAT(EKF_ATT_V4_R0, 0.0008f);
+/* accel measurement noise */
+PARAM_DEFINE_FLOAT(EKF_ATT_V4_R1, 10000.0f);
+/* mag measurement noise */
+PARAM_DEFINE_FLOAT(EKF_ATT_V4_R2, 100.0f);
+/* offset estimation - UNUSED */
+PARAM_DEFINE_FLOAT(EKF_ATT_V4_R3, 0.0f);
/* offsets in roll, pitch and yaw of sensor plane and body */
-PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f);
-PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f);
-PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_ROLL_OFF3, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_PITCH_OFF3, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_YAW_OFF3, 0.0f);
int parameters_init(struct attitude_estimator_ekf_param_handles *h)
{
/* PID parameters */
- h->q0 = param_find("EKF_ATT_V2_Q0");
- h->q1 = param_find("EKF_ATT_V2_Q1");
- h->q2 = param_find("EKF_ATT_V2_Q2");
- h->q3 = param_find("EKF_ATT_V2_Q3");
- h->q4 = param_find("EKF_ATT_V2_Q4");
+ h->q0 = param_find("EKF_ATT_V3_Q0");
+ h->q1 = param_find("EKF_ATT_V3_Q1");
+ h->q2 = param_find("EKF_ATT_V3_Q2");
+ h->q3 = param_find("EKF_ATT_V3_Q3");
+ h->q4 = param_find("EKF_ATT_V3_Q4");
- h->r0 = param_find("EKF_ATT_V2_R0");
- h->r1 = param_find("EKF_ATT_V2_R1");
- h->r2 = param_find("EKF_ATT_V2_R2");
- h->r3 = param_find("EKF_ATT_V2_R3");
+ h->r0 = param_find("EKF_ATT_V4_R0");
+ h->r1 = param_find("EKF_ATT_V4_R1");
+ h->r2 = param_find("EKF_ATT_V4_R2");
+ h->r3 = param_find("EKF_ATT_V4_R3");
- h->roll_off = param_find("ATT_ROLL_OFFS");
- h->pitch_off = param_find("ATT_PITCH_OFFS");
- h->yaw_off = param_find("ATT_YAW_OFFS");
+ h->roll_off = param_find("ATT_ROLL_OFF3");
+ h->pitch_off = param_find("ATT_PITCH_OFF3");
+ h->yaw_off = param_find("ATT_YAW_OFF3");
return OK;
}
diff --git a/src/modules/attitude_estimator_so3/README b/src/modules/attitude_estimator_so3/README
new file mode 100644
index 000000000..02ab66ee4
--- /dev/null
+++ b/src/modules/attitude_estimator_so3/README
@@ -0,0 +1,3 @@
+Synopsis
+
+ nsh> attitude_estimator_so3_comp start \ No newline at end of file
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
new file mode 100755
index 000000000..e79726613
--- /dev/null
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -0,0 +1,678 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Hyon Lim <limhyon@gmail.com>
+ * Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 attitude_estimator_so3_main.cpp
+ *
+ * Implementation of nonlinear complementary filters on the SO(3).
+ * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
+ * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
+ *
+ * Theory of nonlinear complementary filters on the SO(3) is based on [1].
+ * Quaternion realization of [1] is based on [2].
+ * Optmized quaternion update code is based on Sebastian Madgwick's implementation.
+ *
+ * References
+ * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008
+ * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <poll.h>
+#include <fcntl.h>
+#include <float.h>
+#include <nuttx/sched.h>
+#include <sys/prctl.h>
+#include <termios.h>
+#include <errno.h>
+#include <limits.h>
+#include <math.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/debug_key_value.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/parameter_update.h>
+#include <drivers/drv_hrt.h>
+
+#include <systemlib/systemlib.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+#include "attitude_estimator_so3_params.h"
+#ifdef __cplusplus
+}
+#endif
+
+extern "C" __EXPORT int attitude_estimator_so3_main(int argc, char *argv[]);
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int attitude_estimator_so3_task; /**< Handle of deamon task / thread */
+
+//! Auxiliary variables to reduce number of repeated operations
+static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */
+static float dq0 = 0.0f, dq1 = 0.0f, dq2 = 0.0f, dq3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */
+static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */
+static float q0q0, q0q1, q0q2, q0q3;
+static float q1q1, q1q2, q1q3;
+static float q2q2, q2q3;
+static float q3q3;
+static bool bFilterInit = false;
+
+/**
+ * Mainloop of attitude_estimator_so3.
+ */
+int attitude_estimator_so3_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason);
+
+/* Function prototypes */
+float invSqrt(float number);
+void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz);
+void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt);
+
+static void
+usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: attitude_estimator_so3 {start|stop|status}\n");
+ exit(1);
+}
+
+/**
+ * The attitude_estimator_so3 app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int attitude_estimator_so3_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ attitude_estimator_so3_task = task_spawn_cmd("attitude_estimator_so3",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 14000,
+ attitude_estimator_so3_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+
+ while (thread_running){
+ usleep(200000);
+ }
+
+ warnx("stopped");
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("running");
+ exit(0);
+
+ } else {
+ warnx("not started");
+ exit(1);
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+//---------------------------------------------------------------------------------------------------
+// Fast inverse square-root
+// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
+float invSqrt(float number)
+{
+ volatile long i;
+ volatile float x, y;
+ volatile const float f = 1.5F;
+
+ x = number * 0.5F;
+ y = number;
+ i = * (( long * ) &y);
+ i = 0x5f375a86 - ( i >> 1 );
+ y = * (( float * ) &i);
+ y = y * ( f - ( x * y * y ) );
+ return y;
+}
+
+//! Using accelerometer, sense the gravity vector.
+//! Using magnetometer, sense yaw.
+void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz)
+{
+ float initialRoll, initialPitch;
+ float cosRoll, sinRoll, cosPitch, sinPitch;
+ float magX, magY;
+ float initialHdg, cosHeading, sinHeading;
+
+ initialRoll = atan2(-ay, -az);
+ initialPitch = atan2(ax, -az);
+
+ cosRoll = cosf(initialRoll);
+ sinRoll = sinf(initialRoll);
+ cosPitch = cosf(initialPitch);
+ sinPitch = sinf(initialPitch);
+
+ magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
+
+ magY = my * cosRoll - mz * sinRoll;
+
+ initialHdg = atan2f(-magY, magX);
+
+ cosRoll = cosf(initialRoll * 0.5f);
+ sinRoll = sinf(initialRoll * 0.5f);
+
+ cosPitch = cosf(initialPitch * 0.5f);
+ sinPitch = sinf(initialPitch * 0.5f);
+
+ cosHeading = cosf(initialHdg * 0.5f);
+ sinHeading = sinf(initialHdg * 0.5f);
+
+ q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
+ q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
+ q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
+ q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
+
+ // auxillary variables to reduce number of repeated operations, for 1st pass
+ q0q0 = q0 * q0;
+ q0q1 = q0 * q1;
+ q0q2 = q0 * q2;
+ q0q3 = q0 * q3;
+ q1q1 = q1 * q1;
+ q1q2 = q1 * q2;
+ q1q3 = q1 * q3;
+ q2q2 = q2 * q2;
+ q2q3 = q2 * q3;
+ q3q3 = q3 * q3;
+}
+
+void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt)
+{
+ float recipNorm;
+ float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f;
+
+ // Make filter converge to initial solution faster
+ // This function assumes you are in static position.
+ // WARNING : in case air reboot, this can cause problem. But this is very unlikely happen.
+ if(bFilterInit == false) {
+ NonlinearSO3AHRSinit(ax,ay,az,mx,my,mz);
+ bFilterInit = true;
+ }
+
+ //! If magnetometer measurement is available, use it.
+ if(!((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f))) {
+ float hx, hy, hz, bx, bz;
+ float halfwx, halfwy, halfwz;
+
+ // Normalise magnetometer measurement
+ // Will sqrt work better? PX4 system is powerful enough?
+ recipNorm = invSqrt(mx * mx + my * my + mz * mz);
+ mx *= recipNorm;
+ my *= recipNorm;
+ mz *= recipNorm;
+
+ // Reference direction of Earth's magnetic field
+ hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2));
+ hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1));
+ hz = 2.0f * mx * (q1q3 - q0q2) + 2.0f * my * (q2q3 + q0q1) + 2.0f * mz * (0.5f - q1q1 - q2q2);
+ bx = sqrt(hx * hx + hy * hy);
+ bz = hz;
+
+ // Estimated direction of magnetic field
+ halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2);
+ halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3);
+ halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2);
+
+ // Error is sum of cross product between estimated direction and measured direction of field vectors
+ halfex += (my * halfwz - mz * halfwy);
+ halfey += (mz * halfwx - mx * halfwz);
+ halfez += (mx * halfwy - my * halfwx);
+ }
+
+ // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
+ if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
+ float halfvx, halfvy, halfvz;
+
+ // Normalise accelerometer measurement
+ recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+ ax *= recipNorm;
+ ay *= recipNorm;
+ az *= recipNorm;
+
+ // Estimated direction of gravity and magnetic field
+ halfvx = q1q3 - q0q2;
+ halfvy = q0q1 + q2q3;
+ halfvz = q0q0 - 0.5f + q3q3;
+
+ // Error is sum of cross product between estimated direction and measured direction of field vectors
+ halfex += ay * halfvz - az * halfvy;
+ halfey += az * halfvx - ax * halfvz;
+ halfez += ax * halfvy - ay * halfvx;
+ }
+
+ // Apply feedback only when valid data has been gathered from the accelerometer or magnetometer
+ if(halfex != 0.0f && halfey != 0.0f && halfez != 0.0f) {
+ // Compute and apply integral feedback if enabled
+ if(twoKi > 0.0f) {
+ gyro_bias[0] += twoKi * halfex * dt; // integral error scaled by Ki
+ gyro_bias[1] += twoKi * halfey * dt;
+ gyro_bias[2] += twoKi * halfez * dt;
+
+ // apply integral feedback
+ gx += gyro_bias[0];
+ gy += gyro_bias[1];
+ gz += gyro_bias[2];
+ }
+ else {
+ gyro_bias[0] = 0.0f; // prevent integral windup
+ gyro_bias[1] = 0.0f;
+ gyro_bias[2] = 0.0f;
+ }
+
+ // Apply proportional feedback
+ gx += twoKp * halfex;
+ gy += twoKp * halfey;
+ gz += twoKp * halfez;
+ }
+
+ //! Integrate rate of change of quaternion
+#if 0
+ gx *= (0.5f * dt); // pre-multiply common factors
+ gy *= (0.5f * dt);
+ gz *= (0.5f * dt);
+#endif
+
+ // Time derivative of quaternion. q_dot = 0.5*q\otimes omega.
+ //! q_k = q_{k-1} + dt*\dot{q}
+ //! \dot{q} = 0.5*q \otimes P(\omega)
+ dq0 = 0.5f*(-q1 * gx - q2 * gy - q3 * gz);
+ dq1 = 0.5f*(q0 * gx + q2 * gz - q3 * gy);
+ dq2 = 0.5f*(q0 * gy - q1 * gz + q3 * gx);
+ dq3 = 0.5f*(q0 * gz + q1 * gy - q2 * gx);
+
+ q0 += dt*dq0;
+ q1 += dt*dq1;
+ q2 += dt*dq2;
+ q3 += dt*dq3;
+
+ // Normalise quaternion
+ recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
+ q0 *= recipNorm;
+ q1 *= recipNorm;
+ q2 *= recipNorm;
+ q3 *= recipNorm;
+
+ // Auxiliary variables to avoid repeated arithmetic
+ q0q0 = q0 * q0;
+ q0q1 = q0 * q1;
+ q0q2 = q0 * q2;
+ q0q3 = q0 * q3;
+ q1q1 = q1 * q1;
+ q1q2 = q1 * q2;
+ q1q3 = q1 * q3;
+ q2q2 = q2 * q2;
+ q2q3 = q2 * q3;
+ q3q3 = q3 * q3;
+}
+
+/*
+ * Nonliner complementary filter on SO(3), attitude estimator main function.
+ *
+ * Estimates the attitude once started.
+ *
+ * @param argc number of commandline arguments (plus command name)
+ * @param argv strings containing the arguments
+ */
+int attitude_estimator_so3_thread_main(int argc, char *argv[])
+{
+ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
+
+ //! Time constant
+ float dt = 0.005f;
+
+ /* output euler angles */
+ float euler[3] = {0.0f, 0.0f, 0.0f};
+
+ /* Initialization */
+ float Rot_matrix[9] = {1.f, 0.0f, 0.0f, 0.0f, 1.f, 0.0f, 0.0f, 0.0f, 1.f }; /**< init: identity matrix */
+ float acc[3] = {0.0f, 0.0f, 0.0f};
+ float gyro[3] = {0.0f, 0.0f, 0.0f};
+ float mag[3] = {0.0f, 0.0f, 0.0f};
+
+ warnx("main thread started");
+
+ struct sensor_combined_s raw;
+ memset(&raw, 0, sizeof(raw));
+
+ //! Initialize attitude vehicle uORB message.
+ struct vehicle_attitude_s att;
+ memset(&att, 0, sizeof(att));
+
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
+
+ uint64_t last_data = 0;
+ uint64_t last_measurement = 0;
+
+ /* subscribe to raw data */
+ int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
+ /* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */
+ orb_set_interval(sub_raw, 3);
+
+ /* subscribe to param changes */
+ int sub_params = orb_subscribe(ORB_ID(parameter_update));
+
+ /* subscribe to control mode */
+ int sub_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
+
+ /* advertise attitude */
+ //orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
+ //orb_advert_t att_pub = -1;
+ orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
+
+ int loopcounter = 0;
+ int printcounter = 0;
+
+ thread_running = true;
+
+ float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
+ // XXX write this out to perf regs
+
+ /* keep track of sensor updates */
+ uint32_t sensor_last_count[3] = {0, 0, 0};
+ uint64_t sensor_last_timestamp[3] = {0, 0, 0};
+
+ struct attitude_estimator_so3_params so3_comp_params;
+ struct attitude_estimator_so3_param_handles so3_comp_param_handles;
+
+ /* initialize parameter handles */
+ parameters_init(&so3_comp_param_handles);
+ parameters_update(&so3_comp_param_handles, &so3_comp_params);
+
+ uint64_t start_time = hrt_absolute_time();
+ bool initialized = false;
+ bool state_initialized = false;
+
+ float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
+ unsigned offset_count = 0;
+
+ /* register the perf counter */
+ perf_counter_t so3_comp_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_so3");
+
+ /* Main loop*/
+ while (!thread_should_exit) {
+
+ struct pollfd fds[2];
+ fds[0].fd = sub_raw;
+ fds[0].events = POLLIN;
+ fds[1].fd = sub_params;
+ fds[1].events = POLLIN;
+ int ret = poll(fds, 2, 1000);
+
+ if (ret < 0) {
+ /* XXX this is seriously bad - should be an emergency */
+ } else if (ret == 0) {
+ /* check if we're in HIL - not getting sensor data is fine then */
+ orb_copy(ORB_ID(vehicle_control_mode), sub_control_mode, &control_mode);
+
+ if (!control_mode.flag_system_hil_enabled) {
+ warnx("WARNING: Not getting sensors - sensor app running?");
+ }
+ } else {
+ /* only update parameters if they changed */
+ if (fds[1].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), sub_params, &update);
+
+ /* update parameters */
+ parameters_update(&so3_comp_param_handles, &so3_comp_params);
+ }
+
+ /* only run filter if sensor values changed */
+ if (fds[0].revents & POLLIN) {
+
+ /* get latest measurements */
+ orb_copy(ORB_ID(sensor_combined), sub_raw, &raw);
+
+ if (!initialized) {
+
+ gyro_offsets[0] += raw.gyro_rad_s[0];
+ gyro_offsets[1] += raw.gyro_rad_s[1];
+ gyro_offsets[2] += raw.gyro_rad_s[2];
+ offset_count++;
+
+ if (hrt_absolute_time() > start_time + 3000000l) {
+ initialized = true;
+ gyro_offsets[0] /= offset_count;
+ gyro_offsets[1] /= offset_count;
+ gyro_offsets[2] /= offset_count;
+ warnx("gyro initialized, offsets: %.5f %.5f %.5f", gyro_offsets[0], gyro_offsets[1], gyro_offsets[2]);
+ }
+
+ } else {
+
+ perf_begin(so3_comp_loop_perf);
+
+ /* Calculate data time difference in seconds */
+ dt = (raw.timestamp - last_measurement) / 1000000.0f;
+ last_measurement = raw.timestamp;
+ uint8_t update_vect[3] = {0, 0, 0};
+
+ /* Fill in gyro measurements */
+ if (sensor_last_count[0] != raw.gyro_counter) {
+ update_vect[0] = 1;
+ sensor_last_count[0] = raw.gyro_counter;
+ sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
+ sensor_last_timestamp[0] = raw.timestamp;
+ }
+
+ gyro[0] = raw.gyro_rad_s[0] - gyro_offsets[0];
+ gyro[1] = raw.gyro_rad_s[1] - gyro_offsets[1];
+ gyro[2] = raw.gyro_rad_s[2] - gyro_offsets[2];
+
+ /* update accelerometer measurements */
+ if (sensor_last_count[1] != raw.accelerometer_counter) {
+ update_vect[1] = 1;
+ sensor_last_count[1] = raw.accelerometer_counter;
+ sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
+ sensor_last_timestamp[1] = raw.timestamp;
+ }
+
+ acc[0] = raw.accelerometer_m_s2[0];
+ acc[1] = raw.accelerometer_m_s2[1];
+ acc[2] = raw.accelerometer_m_s2[2];
+
+ /* update magnetometer measurements */
+ if (sensor_last_count[2] != raw.magnetometer_counter) {
+ update_vect[2] = 1;
+ sensor_last_count[2] = raw.magnetometer_counter;
+ sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
+ sensor_last_timestamp[2] = raw.timestamp;
+ }
+
+ mag[0] = raw.magnetometer_ga[0];
+ mag[1] = raw.magnetometer_ga[1];
+ mag[2] = raw.magnetometer_ga[2];
+
+ /* initialize with good values once we have a reasonable dt estimate */
+ if (!state_initialized && dt < 0.05f && dt > 0.001f) {
+ state_initialized = true;
+ warnx("state initialized");
+ }
+
+ /* do not execute the filter if not initialized */
+ if (!state_initialized) {
+ continue;
+ }
+
+ uint64_t timing_start = hrt_absolute_time();
+
+ // NOTE : Accelerometer is reversed.
+ // Because proper mount of PX4 will give you a reversed accelerometer readings.
+ NonlinearSO3AHRSupdate(gyro[0], gyro[1], gyro[2],
+ -acc[0], -acc[1], -acc[2],
+ mag[0], mag[1], mag[2],
+ so3_comp_params.Kp,
+ so3_comp_params.Ki,
+ dt);
+
+ // Convert q->R, This R converts inertial frame to body frame.
+ Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11
+ Rot_matrix[1] = 2.f * (q1*q2 + q0*q3); // 12
+ Rot_matrix[2] = 2.f * (q1*q3 - q0*q2); // 13
+ Rot_matrix[3] = 2.f * (q1*q2 - q0*q3); // 21
+ Rot_matrix[4] = q0q0 - q1q1 + q2q2 - q3q3;// 22
+ Rot_matrix[5] = 2.f * (q2*q3 + q0*q1); // 23
+ Rot_matrix[6] = 2.f * (q1*q3 + q0*q2); // 31
+ Rot_matrix[7] = 2.f * (q2*q3 - q0*q1); // 32
+ Rot_matrix[8] = q0q0 - q1q1 - q2q2 + q3q3;// 33
+
+ //1-2-3 Representation.
+ //Equation (290)
+ //Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors, James Diebel.
+ // Existing PX4 EKF code was generated by MATLAB which uses coloum major order matrix.
+ euler[0] = atan2f(Rot_matrix[5], Rot_matrix[8]); //! Roll
+ euler[1] = -asinf(Rot_matrix[2]); //! Pitch
+ euler[2] = atan2f(Rot_matrix[1], Rot_matrix[0]); //! Yaw
+
+ /* swap values for next iteration, check for fatal inputs */
+ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) {
+ // Publish only finite euler angles
+ att.roll = euler[0] - so3_comp_params.roll_off;
+ att.pitch = euler[1] - so3_comp_params.pitch_off;
+ att.yaw = euler[2] - so3_comp_params.yaw_off;
+ } else {
+ /* due to inputs or numerical failure the output is invalid, skip it */
+ // Due to inputs or numerical failure the output is invalid
+ warnx("infinite euler angles, rotation matrix:");
+ warnx("%.3f %.3f %.3f", Rot_matrix[0], Rot_matrix[1], Rot_matrix[2]);
+ warnx("%.3f %.3f %.3f", Rot_matrix[3], Rot_matrix[4], Rot_matrix[5]);
+ warnx("%.3f %.3f %.3f", Rot_matrix[6], Rot_matrix[7], Rot_matrix[8]);
+ // Don't publish anything
+ continue;
+ }
+
+ if (last_data > 0 && raw.timestamp > last_data + 12000) {
+ warnx("sensor data missed");
+ }
+
+ last_data = raw.timestamp;
+
+ /* send out */
+ att.timestamp = raw.timestamp;
+
+ // Quaternion
+ att.q[0] = q0;
+ att.q[1] = q1;
+ att.q[2] = q2;
+ att.q[3] = q3;
+ att.q_valid = true;
+
+ // Euler angle rate. But it needs to be investigated again.
+ /*
+ att.rollspeed = 2.0f*(-q1*dq0 + q0*dq1 - q3*dq2 + q2*dq3);
+ att.pitchspeed = 2.0f*(-q2*dq0 + q3*dq1 + q0*dq2 - q1*dq3);
+ att.yawspeed = 2.0f*(-q3*dq0 -q2*dq1 + q1*dq2 + q0*dq3);
+ */
+ att.rollspeed = gyro[0];
+ att.pitchspeed = gyro[1];
+ att.yawspeed = gyro[2];
+
+ att.rollacc = 0;
+ att.pitchacc = 0;
+ att.yawacc = 0;
+
+ /* TODO: Bias estimation required */
+ memcpy(&att.rate_offsets, &(gyro_bias), sizeof(att.rate_offsets));
+
+ /* copy rotation matrix */
+ memcpy(&att.R, Rot_matrix, sizeof(float)*9);
+ att.R_valid = true;
+
+ // Publish
+ if (att_pub > 0) {
+ orb_publish(ORB_ID(vehicle_attitude), att_pub, &att);
+ } else {
+ warnx("NaN in roll/pitch/yaw estimate!");
+ orb_advertise(ORB_ID(vehicle_attitude), &att);
+ }
+
+ perf_end(so3_comp_loop_perf);
+ }
+ }
+ }
+
+ loopcounter++;
+ }
+
+ thread_running = false;
+
+ return 0;
+}
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_params.c b/src/modules/attitude_estimator_so3/attitude_estimator_so3_params.c
new file mode 100755
index 000000000..0c8d522b4
--- /dev/null
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_params.c
@@ -0,0 +1,86 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Hyon Lim <limhyon@gmail.com>
+ * Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 attitude_estimator_so3_params.c
+ *
+ * Parameters for nonlinear complementary filters on the SO(3).
+ */
+
+#include "attitude_estimator_so3_params.h"
+
+/* This is filter gain for nonlinear SO3 complementary filter */
+/* NOTE : How to tune the gain? First of all, stick with this default gain. And let the quad in stable place.
+ Log the steady state reponse of filter. If it is too slow, increase SO3_COMP_KP.
+ If you are flying from ground to high altitude in short amount of time, please increase SO3_COMP_KI which
+ will compensate gyro bias which depends on temperature and vibration of your vehicle */
+PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); //! This parameter will give you about 15 seconds convergence time.
+ //! You can set this gain higher if you want more fast response.
+ //! But note that higher gain will give you also higher overshoot.
+PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.05f); //! This gain will incorporate slow time-varying bias (e.g., temperature change)
+ //! This gain is depend on your vehicle status.
+
+/* offsets in roll, pitch and yaw of sensor plane and body */
+PARAM_DEFINE_FLOAT(SO3_ROLL_OFFS, 0.0f);
+PARAM_DEFINE_FLOAT(SO3_PITCH_OFFS, 0.0f);
+PARAM_DEFINE_FLOAT(SO3_YAW_OFFS, 0.0f);
+
+int parameters_init(struct attitude_estimator_so3_param_handles *h)
+{
+ /* Filter gain parameters */
+ h->Kp = param_find("SO3_COMP_KP");
+ h->Ki = param_find("SO3_COMP_KI");
+
+ /* Attitude offset (WARNING: Do not change if you do not know what exactly this variable wil lchange) */
+ h->roll_off = param_find("SO3_ROLL_OFFS");
+ h->pitch_off = param_find("SO3_PITCH_OFFS");
+ h->yaw_off = param_find("SO3_YAW_OFFS");
+
+ return OK;
+}
+
+int parameters_update(const struct attitude_estimator_so3_param_handles *h, struct attitude_estimator_so3_params *p)
+{
+ /* Update filter gain */
+ param_get(h->Kp, &(p->Kp));
+ param_get(h->Ki, &(p->Ki));
+
+ /* Update attitude offset */
+ param_get(h->roll_off, &(p->roll_off));
+ param_get(h->pitch_off, &(p->pitch_off));
+ param_get(h->yaw_off, &(p->yaw_off));
+
+ return OK;
+}
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_params.h b/src/modules/attitude_estimator_so3/attitude_estimator_so3_params.h
new file mode 100755
index 000000000..dfb4cad05
--- /dev/null
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_params.h
@@ -0,0 +1,67 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Hyon Lim <limhyon@gmail.com>
+ * Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 attitude_estimator_so3_params.h
+ *
+ * Parameters for nonlinear complementary filters on the SO(3).
+ */
+
+#include <systemlib/param/param.h>
+
+struct attitude_estimator_so3_params {
+ float Kp;
+ float Ki;
+ float roll_off;
+ float pitch_off;
+ float yaw_off;
+};
+
+struct attitude_estimator_so3_param_handles {
+ param_t Kp, Ki;
+ param_t roll_off, pitch_off, yaw_off;
+};
+
+/**
+ * Initialize all parameter handles and values
+ *
+ */
+int parameters_init(struct attitude_estimator_so3_param_handles *h);
+
+/**
+ * Update all parameters
+ *
+ */
+int parameters_update(const struct attitude_estimator_so3_param_handles *h, struct attitude_estimator_so3_params *p);
diff --git a/src/modules/attitude_estimator_so3/module.mk b/src/modules/attitude_estimator_so3/module.mk
new file mode 100644
index 000000000..e29bb16a6
--- /dev/null
+++ b/src/modules/attitude_estimator_so3/module.mk
@@ -0,0 +1,8 @@
+#
+# Attitude estimator (Nonlinear SO(3) complementary Filter)
+#
+
+MODULE_COMMAND = attitude_estimator_so3
+
+SRCS = attitude_estimator_so3_main.cpp \
+ attitude_estimator_so3_params.c
diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c
deleted file mode 100644
index d79dd93dd..000000000
--- a/src/modules/commander/accelerometer_calibration.c
+++ /dev/null
@@ -1,414 +0,0 @@
-/*
- * accelerometer_calibration.c
- *
- * Copyright (C) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
- *
- * Transform acceleration vector to true orientation and scale
- *
- * * * * Model * * *
- * accel_corr = accel_T * (accel_raw - accel_offs)
- *
- * accel_corr[3] - fully corrected acceleration vector in body frame
- * accel_T[3][3] - accelerometers transform matrix, rotation and scaling transform
- * accel_raw[3] - raw acceleration vector
- * accel_offs[3] - acceleration offset vector
- *
- * * * * Calibration * * *
- *
- * Reference vectors
- * accel_corr_ref[6][3] = [ g 0 0 ] // nose up
- * | -g 0 0 | // nose down
- * | 0 g 0 | // left side down
- * | 0 -g 0 | // right side down
- * | 0 0 g | // on back
- * [ 0 0 -g ] // level
- * accel_raw_ref[6][3]
- *
- * accel_corr_ref[i] = accel_T * (accel_raw_ref[i] - accel_offs), i = 0...5
- *
- * 6 reference vectors * 3 axes = 18 equations
- * 9 (accel_T) + 3 (accel_offs) = 12 unknown constants
- *
- * Find accel_offs
- *
- * accel_offs[i] = (accel_raw_ref[i*2][i] + accel_raw_ref[i*2+1][i]) / 2
- *
- *
- * Find accel_T
- *
- * 9 unknown constants
- * need 9 equations -> use 3 of 6 measurements -> 3 * 3 = 9 equations
- *
- * accel_corr_ref[i*2] = accel_T * (accel_raw_ref[i*2] - accel_offs), i = 0...2
- *
- * Solve separate system for each row of accel_T:
- *
- * accel_corr_ref[j*2][i] = accel_T[i] * (accel_raw_ref[j*2] - accel_offs), j = 0...2
- *
- * A * x = b
- *
- * x = [ accel_T[0][i] ]
- * | accel_T[1][i] |
- * [ accel_T[2][i] ]
- *
- * b = [ accel_corr_ref[0][i] ] // One measurement per axis is enough
- * | accel_corr_ref[2][i] |
- * [ accel_corr_ref[4][i] ]
- *
- * a[i][j] = accel_raw_ref[i][j] - accel_offs[j], i = 0;2;4, j = 0...2
- *
- * Matrix A is common for all three systems:
- * A = [ a[0][0] a[0][1] a[0][2] ]
- * | a[2][0] a[2][1] a[2][2] |
- * [ a[4][0] a[4][1] a[4][2] ]
- *
- * x = A^-1 * b
- *
- * accel_T = A^-1 * g
- * g = 9.80665
- */
-
-#include "accelerometer_calibration.h"
-
-#include <poll.h>
-#include <drivers/drv_hrt.h>
-#include <uORB/topics/sensor_combined.h>
-#include <drivers/drv_accel.h>
-#include <systemlib/conversions.h>
-#include <mavlink/mavlink_log.h>
-
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd);
-int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]);
-int detect_orientation(int mavlink_fd, int sub_sensor_combined);
-int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num);
-int mat_invert3(float src[3][3], float dst[3][3]);
-int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g);
-
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) {
- /* announce change */
- mavlink_log_info(mavlink_fd, "accel calibration started");
- /* set to accel calibration mode */
- status->flag_preflight_accel_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- /* measure and calculate offsets & scales */
- float accel_offs[3];
- float accel_scale[3];
- int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs, accel_scale);
-
- if (res == OK) {
- /* measurements complete successfully, set parameters */
- if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs[0]))
- || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs[1]))
- || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs[2]))
- || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0]))
- || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1]))
- || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) {
- mavlink_log_critical(mavlink_fd, "ERROR: setting offs or scale failed");
- }
-
- int fd = open(ACCEL_DEVICE_PATH, 0);
- struct accel_scale ascale = {
- accel_offs[0],
- accel_scale[0],
- accel_offs[1],
- accel_scale[1],
- accel_offs[2],
- accel_scale[2],
- };
-
- if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale))
- warn("WARNING: failed to set scale / offsets for accel");
-
- close(fd);
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- mavlink_log_info(mavlink_fd, "accel calibration done");
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
- } else {
- /* measurements error */
- mavlink_log_info(mavlink_fd, "accel calibration aborted");
- tune_error();
- sleep(2);
- }
-
- /* exit accel calibration mode */
- status->flag_preflight_accel_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-}
-
-int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) {
- 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-" };
-
- /* reset existing calibration */
- int fd = open(ACCEL_DEVICE_PATH, 0);
- struct accel_scale ascale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
- int ioctl_res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale_null);
- close(fd);
-
- if (OK != ioctl_res) {
- warn("ERROR: failed to set scale / offsets for accel");
- return ERROR;
- }
-
- int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
- while (true) {
- bool done = true;
- char str[80];
- int str_ptr;
- str_ptr = sprintf(str, "keep vehicle still:");
- for (int i = 0; i < 6; i++) {
- if (!data_collected[i]) {
- str_ptr += sprintf(&(str[str_ptr]), " %s", orientation_strs[i]);
- done = false;
- }
- }
- if (done)
- break;
- mavlink_log_info(mavlink_fd, str);
-
- int orient = detect_orientation(mavlink_fd, sensor_combined_sub);
- if (orient < 0)
- return ERROR;
-
- sprintf(str, "meas started: %s", orientation_strs[orient]);
- mavlink_log_info(mavlink_fd, str);
- read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num);
- str_ptr = sprintf(str, "meas result for %s: [ %.2f %.2f %.2f ]", orientation_strs[orient], accel_ref[orient][0], accel_ref[orient][1], accel_ref[orient][2]);
- mavlink_log_info(mavlink_fd, str);
- data_collected[orient] = true;
- tune_confirm();
- }
- close(sensor_combined_sub);
-
- /* calculate offsets and rotation+scale matrix */
- float accel_T[3][3];
- int res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G);
- if (res != 0) {
- mavlink_log_info(mavlink_fd, "ERROR: calibration values calc error");
- return ERROR;
- }
-
- /* convert accel transform matrix to scales,
- * rotation part of transform matrix is not used by now
- */
- for (int i = 0; i < 3; i++) {
- accel_scale[i] = accel_T[i][i];
- }
-
- return OK;
-}
-
-/*
- * Wait for vehicle become still and detect it's orientation.
- *
- * @return 0..5 according to orientation when vehicle is still and ready for measurements,
- * ERROR if vehicle is not still after 30s or orientation error is more than 5m/s^2
- */
-int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
- struct sensor_combined_s sensor;
- /* exponential moving average of accel */
- float accel_ema[3] = { 0.0f, 0.0f, 0.0f };
- /* max-hold dispersion of accel */
- float accel_disp[3] = { 0.0f, 0.0f, 0.0f };
- /* EMA time constant in seconds*/
- float ema_len = 0.2f;
- /* set "still" threshold to 0.1 m/s^2 */
- float still_thr2 = pow(0.1f, 2);
- /* set accel error threshold to 5m/s^2 */
- float accel_err_thr = 5.0f;
- /* still time required in us */
- int64_t still_time = 2000000;
- struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
-
- hrt_abstime t_start = hrt_absolute_time();
- /* set timeout to 30s */
- hrt_abstime timeout = 30000000;
- hrt_abstime t_timeout = t_start + timeout;
- hrt_abstime t = t_start;
- hrt_abstime t_prev = t_start;
- hrt_abstime t_still = 0;
- while (true) {
- /* wait blocking for new data */
- int poll_ret = poll(fds, 1, 1000);
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &sensor);
- t = hrt_absolute_time();
- float dt = (t - t_prev) / 1000000.0f;
- t_prev = t;
- float w = dt / ema_len;
- for (int i = 0; i < 3; i++) {
- accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_m_s2[i] * w;
- float d = (float) sensor.accelerometer_m_s2[i] - accel_ema[i];
- d = d * d;
- accel_disp[i] = accel_disp[i] * (1.0f - w);
- if (d > accel_disp[i])
- accel_disp[i] = d;
- }
- /* still detector with hysteresis */
- if ( accel_disp[0] < still_thr2 &&
- accel_disp[1] < still_thr2 &&
- accel_disp[2] < still_thr2 ) {
- /* is still now */
- if (t_still == 0) {
- /* first time */
- mavlink_log_info(mavlink_fd, "still...");
- t_still = t;
- t_timeout = t + timeout;
- } else {
- /* still since t_still */
- if ((int64_t) t - (int64_t) t_still > still_time) {
- /* vehicle is still, exit from the loop to detection of its orientation */
- break;
- }
- }
- } else if ( accel_disp[0] > still_thr2 * 2.0f ||
- accel_disp[1] > still_thr2 * 2.0f ||
- accel_disp[2] > still_thr2 * 2.0f) {
- /* not still, reset still start time */
- if (t_still != 0) {
- mavlink_log_info(mavlink_fd, "moving...");
- t_still = 0;
- }
- }
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "ERROR: poll failure");
- return -3;
- }
- if (t > t_timeout) {
- mavlink_log_info(mavlink_fd, "ERROR: timeout");
- return -1;
- }
- }
-
- if ( fabs(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
- return 0; // [ g, 0, 0 ]
- if ( fabs(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
- return 1; // [ -g, 0, 0 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
- return 2; // [ 0, g, 0 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
- return 3; // [ 0, -g, 0 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr )
- return 4; // [ 0, 0, g ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr )
- return 5; // [ 0, 0, -g ]
-
- mavlink_log_info(mavlink_fd, "ERROR: invalid orientation");
-
- return -2; // Can't detect orientation
-}
-
-/*
- * Read specified number of accelerometer samples, calculate average and dispersion.
- */
-int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num) {
- struct pollfd fds[1] = { { .fd = sensor_combined_sub, .events = POLLIN } };
- int count = 0;
- float accel_sum[3] = { 0.0f, 0.0f, 0.0f };
-
- while (count < samples_num) {
- int poll_ret = poll(fds, 1, 1000);
- if (poll_ret == 1) {
- struct sensor_combined_s sensor;
- orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- for (int i = 0; i < 3; i++)
- accel_sum[i] += sensor.accelerometer_m_s2[i];
- count++;
- } else {
- return ERROR;
- }
- }
-
- for (int i = 0; i < 3; i++) {
- accel_avg[i] = accel_sum[i] / count;
- }
-
- return OK;
-}
-
-int mat_invert3(float src[3][3], float dst[3][3]) {
- float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) -
- src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
- src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0)
- return ERROR; // Singular matrix
-
- dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
- dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det;
- dst[2][0] = (src[1][0] * src[2][1] - src[1][1] * src[2][0]) / det;
- dst[0][1] = (src[0][2] * src[2][1] - src[0][1] * src[2][2]) / det;
- dst[1][1] = (src[0][0] * src[2][2] - src[0][2] * src[2][0]) / det;
- dst[2][1] = (src[0][1] * src[2][0] - src[0][0] * src[2][1]) / det;
- dst[0][2] = (src[0][1] * src[1][2] - src[0][2] * src[1][1]) / det;
- dst[1][2] = (src[0][2] * src[1][0] - src[0][0] * src[1][2]) / det;
- dst[2][2] = (src[0][0] * src[1][1] - src[0][1] * src[1][0]) / det;
-
- return OK;
-}
-
-int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g) {
- /* calculate offsets */
- for (int i = 0; i < 3; i++) {
- accel_offs[i] = (accel_ref[i * 2][i] + accel_ref[i * 2 + 1][i]) / 2;
- }
-
- /* fill matrix A for linear equations system*/
- float mat_A[3][3];
- memset(mat_A, 0, sizeof(mat_A));
- for (int i = 0; i < 3; i++) {
- for (int j = 0; j < 3; j++) {
- float a = accel_ref[i * 2][j] - accel_offs[j];
- mat_A[i][j] = a;
- }
- }
-
- /* calculate inverse matrix for A */
- float mat_A_inv[3][3];
- if (mat_invert3(mat_A, mat_A_inv) != OK)
- return ERROR;
-
- /* copy results to accel_T */
- for (int i = 0; i < 3; i++) {
- for (int j = 0; j < 3; j++) {
- /* simplify matrices mult because b has only one non-zero element == g at index i */
- accel_T[j][i] = mat_A_inv[j][i] * g;
- }
- }
-
- return OK;
-}
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
new file mode 100644
index 000000000..5eeca5a1a
--- /dev/null
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -0,0 +1,566 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 accelerometer_calibration.cpp
+ *
+ * Implementation of accelerometer calibration.
+ *
+ * Transform acceleration vector to true orientation, scale and offset
+ *
+ * ===== Model =====
+ * accel_corr = accel_T * (accel_raw - accel_offs)
+ *
+ * accel_corr[3] - fully corrected acceleration vector in body frame
+ * accel_T[3][3] - accelerometers transform matrix, rotation and scaling transform
+ * accel_raw[3] - raw acceleration vector
+ * accel_offs[3] - acceleration offset vector
+ *
+ * ===== Calibration =====
+ *
+ * Reference vectors
+ * accel_corr_ref[6][3] = [ g 0 0 ] // nose up
+ * | -g 0 0 | // nose down
+ * | 0 g 0 | // left side down
+ * | 0 -g 0 | // right side down
+ * | 0 0 g | // on back
+ * [ 0 0 -g ] // level
+ * accel_raw_ref[6][3]
+ *
+ * accel_corr_ref[i] = accel_T * (accel_raw_ref[i] - accel_offs), i = 0...5
+ *
+ * 6 reference vectors * 3 axes = 18 equations
+ * 9 (accel_T) + 3 (accel_offs) = 12 unknown constants
+ *
+ * Find accel_offs
+ *
+ * accel_offs[i] = (accel_raw_ref[i*2][i] + accel_raw_ref[i*2+1][i]) / 2
+ *
+ * Find accel_T
+ *
+ * 9 unknown constants
+ * need 9 equations -> use 3 of 6 measurements -> 3 * 3 = 9 equations
+ *
+ * accel_corr_ref[i*2] = accel_T * (accel_raw_ref[i*2] - accel_offs), i = 0...2
+ *
+ * Solve separate system for each row of accel_T:
+ *
+ * accel_corr_ref[j*2][i] = accel_T[i] * (accel_raw_ref[j*2] - accel_offs), j = 0...2
+ *
+ * A * x = b
+ *
+ * x = [ accel_T[0][i] ]
+ * | accel_T[1][i] |
+ * [ accel_T[2][i] ]
+ *
+ * b = [ accel_corr_ref[0][i] ] // One measurement per axis is enough
+ * | accel_corr_ref[2][i] |
+ * [ accel_corr_ref[4][i] ]
+ *
+ * a[i][j] = accel_raw_ref[i][j] - accel_offs[j], i = 0;2;4, j = 0...2
+ *
+ * Matrix A is common for all three systems:
+ * A = [ a[0][0] a[0][1] a[0][2] ]
+ * | a[2][0] a[2][1] a[2][2] |
+ * [ a[4][0] a[4][1] a[4][2] ]
+ *
+ * x = A^-1 * b
+ *
+ * accel_T = A^-1 * g
+ * g = 9.80665
+ *
+ * ===== Rotation =====
+ *
+ * Calibrating using model:
+ * accel_corr = accel_T_r * (rot * accel_raw - accel_offs_r)
+ *
+ * Actual correction:
+ * accel_corr = rot * accel_T * (accel_raw - accel_offs)
+ *
+ * Known: accel_T_r, accel_offs_r, rot
+ * Unknown: accel_T, accel_offs
+ *
+ * Solution:
+ * accel_T_r * (rot * accel_raw - accel_offs_r) = rot * accel_T * (accel_raw - accel_offs)
+ * rot^-1 * accel_T_r * (rot * accel_raw - accel_offs_r) = accel_T * (accel_raw - accel_offs)
+ * rot^-1 * accel_T_r * rot * accel_raw - rot^-1 * accel_T_r * accel_offs_r = accel_T * accel_raw - accel_T * accel_offs)
+ * => accel_T = rot^-1 * accel_T_r * rot
+ * => accel_offs = rot^-1 * accel_offs_r
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include "accelerometer_calibration.h"
+#include "calibration_messages.h"
+#include "commander_helper.h"
+
+#include <unistd.h>
+#include <stdio.h>
+#include <poll.h>
+#include <fcntl.h>
+#include <sys/prctl.h>
+#include <math.h>
+#include <mathlib/mathlib.h>
+#include <string.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_accel.h>
+#include <geo/geo.h>
+#include <conversion/rotation.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <mavlink/mavlink_log.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+static const char *sensor_name = "accel";
+
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_T[3][3]);
+int detect_orientation(int mavlink_fd, int sub_sensor_combined);
+int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num);
+int mat_invert3(float src[3][3], float dst[3][3]);
+int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g);
+
+int do_accel_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+
+ struct accel_scale accel_scale = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ int res = OK;
+
+ /* reset all offsets to zero and all scales to one */
+ int fd = open(ACCEL_DEVICE_PATH, 0);
+ res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
+ close(fd);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
+
+ float accel_offs[3];
+ float accel_T[3][3];
+
+ if (res == OK) {
+ /* measure and calculate offsets & scales */
+ res = do_accel_calibration_measurements(mavlink_fd, accel_offs, accel_T);
+ }
+
+ if (res == OK) {
+ /* measurements completed successfully, rotate calibration values */
+ param_t board_rotation_h = param_find("SENS_BOARD_ROT");
+ int32_t board_rotation_int;
+ param_get(board_rotation_h, &(board_rotation_int));
+ enum Rotation board_rotation_id = (enum Rotation)board_rotation_int;
+ math::Matrix board_rotation(3, 3);
+ get_rot_matrix(board_rotation_id, &board_rotation);
+ math::Matrix board_rotation_t = board_rotation.transpose();
+ math::Vector3 accel_offs_vec;
+ accel_offs_vec.set(&accel_offs[0]);
+ math::Vector3 accel_offs_rotated = board_rotation_t * accel_offs_vec;
+ math::Matrix accel_T_mat(3, 3);
+ accel_T_mat.set(&accel_T[0][0]);
+ math::Matrix accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation;
+
+ accel_scale.x_offset = accel_offs_rotated(0);
+ accel_scale.x_scale = accel_T_rotated(0, 0);
+ accel_scale.y_offset = accel_offs_rotated(1);
+ accel_scale.y_scale = accel_T_rotated(1, 1);
+ accel_scale.z_offset = accel_offs_rotated(2);
+ accel_scale.z_scale = accel_T_rotated(2, 2);
+
+ /* set parameters */
+ if (param_set(param_find("SENS_ACC_XOFF"), &(accel_scale.x_offset))
+ || param_set(param_find("SENS_ACC_YOFF"), &(accel_scale.y_offset))
+ || param_set(param_find("SENS_ACC_ZOFF"), &(accel_scale.z_offset))
+ || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale.x_scale))
+ || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale.y_scale))
+ || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale.z_scale))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ res = ERROR;
+ }
+ }
+
+ if (res == OK) {
+ /* apply new scaling and offsets */
+ int fd = open(ACCEL_DEVICE_PATH, 0);
+ res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
+ close(fd);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
+ }
+
+ if (res == OK) {
+ /* auto-save to EEPROM */
+ res = param_save_default();
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
+ }
+ }
+
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
+
+ } else {
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ }
+
+ return res;
+}
+
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_T[3][3])
+{
+ 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-" };
+
+ int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+
+ unsigned done_count = 0;
+ int res = OK;
+
+ while (true) {
+ bool done = true;
+ unsigned old_done_count = done_count;
+ done_count = 0;
+
+ for (int i = 0; i < 6; i++) {
+ if (data_collected[i]) {
+ done_count++;
+
+ } else {
+ done = false;
+ }
+ }
+
+ if (old_done_count != done_count)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
+
+ if (done)
+ 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- " : "");
+
+ int orient = detect_orientation(mavlink_fd, sensor_combined_sub);
+
+ if (orient < 0) {
+ res = ERROR;
+ break;
+ }
+
+ if (data_collected[orient]) {
+ mavlink_log_info(mavlink_fd, "%s done, rotate to a different axis", orientation_strs[orient]);
+ continue;
+ }
+
+ mavlink_log_info(mavlink_fd, "accel measurement started: %s axis", orientation_strs[orient]);
+ 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],
+ (double)accel_ref[orient][0],
+ (double)accel_ref[orient][1],
+ (double)accel_ref[orient][2]);
+
+ data_collected[orient] = true;
+ tune_neutral();
+ }
+
+ close(sensor_combined_sub);
+
+ if (res == OK) {
+ /* calculate offsets and transform matrix */
+ res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G);
+
+ if (res != OK) {
+ mavlink_log_info(mavlink_fd, "ERROR: calibration values calculation error");
+ }
+ }
+
+ return res;
+}
+
+/*
+ * Wait for vehicle become still and detect it's orientation.
+ *
+ * @return 0..5 according to orientation when vehicle is still and ready for measurements,
+ * ERROR if vehicle is not still after 30s or orientation error is more than 5m/s^2
+ */
+int detect_orientation(int mavlink_fd, int sub_sensor_combined)
+{
+ struct sensor_combined_s sensor;
+ /* exponential moving average of accel */
+ float accel_ema[3] = { 0.0f, 0.0f, 0.0f };
+ /* max-hold dispersion of accel */
+ float accel_disp[3] = { 0.0f, 0.0f, 0.0f };
+ /* EMA time constant in seconds*/
+ float ema_len = 0.5f;
+ /* set "still" threshold to 0.25 m/s^2 */
+ float still_thr2 = pow(0.25f, 2);
+ /* set accel error threshold to 5m/s^2 */
+ float accel_err_thr = 5.0f;
+ /* still time required in us */
+ hrt_abstime still_time = 2000000;
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_combined;
+ fds[0].events = POLLIN;
+
+ hrt_abstime t_start = hrt_absolute_time();
+ /* set timeout to 30s */
+ hrt_abstime timeout = 30000000;
+ hrt_abstime t_timeout = t_start + timeout;
+ hrt_abstime t = t_start;
+ hrt_abstime t_prev = t_start;
+ hrt_abstime t_still = 0;
+
+ unsigned poll_errcount = 0;
+
+ while (true) {
+ /* wait blocking for new data */
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &sensor);
+ t = hrt_absolute_time();
+ float dt = (t - t_prev) / 1000000.0f;
+ t_prev = t;
+ float w = dt / ema_len;
+
+ for (int i = 0; i < 3; i++) {
+ float d = sensor.accelerometer_m_s2[i] - accel_ema[i];
+ accel_ema[i] += d * w;
+ d = d * d;
+ accel_disp[i] = accel_disp[i] * (1.0f - w);
+
+ if (d > still_thr2 * 8.0f)
+ d = still_thr2 * 8.0f;
+
+ if (d > accel_disp[i])
+ accel_disp[i] = d;
+ }
+
+ /* still detector with hysteresis */
+ if (accel_disp[0] < still_thr2 &&
+ accel_disp[1] < still_thr2 &&
+ accel_disp[2] < still_thr2) {
+ /* is still now */
+ if (t_still == 0) {
+ /* first time */
+ mavlink_log_info(mavlink_fd, "detected rest position, waiting...");
+ t_still = t;
+ t_timeout = t + timeout;
+
+ } else {
+ /* still since t_still */
+ if (t > t_still + still_time) {
+ /* vehicle is still, exit from the loop to detection of its orientation */
+ break;
+ }
+ }
+
+ } else if (accel_disp[0] > still_thr2 * 4.0f ||
+ accel_disp[1] > still_thr2 * 4.0f ||
+ accel_disp[2] > still_thr2 * 4.0f) {
+ /* not still, reset still start time */
+ if (t_still != 0) {
+ mavlink_log_info(mavlink_fd, "detected motion, hold still...");
+ t_still = 0;
+ }
+ }
+
+ } else if (poll_ret == 0) {
+ poll_errcount++;
+ }
+
+ if (t > t_timeout) {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ return ERROR;
+ }
+ }
+
+ if (fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
+ return 0; // [ g, 0, 0 ]
+
+ if (fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
+ return 1; // [ -g, 0, 0 ]
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
+ return 2; // [ 0, g, 0 ]
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
+ return 3; // [ 0, -g, 0 ]
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr)
+ return 4; // [ 0, 0, g ]
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr)
+ return 5; // [ 0, 0, -g ]
+
+ mavlink_log_critical(mavlink_fd, "ERROR: invalid orientation");
+
+ return ERROR; // Can't detect orientation
+}
+
+/*
+ * Read specified number of accelerometer samples, calculate average and dispersion.
+ */
+int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num)
+{
+ struct pollfd fds[1];
+ fds[0].fd = sensor_combined_sub;
+ fds[0].events = POLLIN;
+ int count = 0;
+ float accel_sum[3] = { 0.0f, 0.0f, 0.0f };
+
+ int errcount = 0;
+
+ while (count < samples_num) {
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret == 1) {
+ struct sensor_combined_s sensor;
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+
+ for (int i = 0; i < 3; i++)
+ accel_sum[i] += sensor.accelerometer_m_s2[i];
+
+ count++;
+
+ } else {
+ errcount++;
+ continue;
+ }
+
+ if (errcount > samples_num / 10)
+ return ERROR;
+ }
+
+ for (int i = 0; i < 3; i++) {
+ accel_avg[i] = accel_sum[i] / count;
+ }
+
+ return OK;
+}
+
+int mat_invert3(float src[3][3], float dst[3][3])
+{
+ float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) -
+ src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
+ src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
+
+ if (det == 0.0f)
+ return ERROR; // Singular matrix
+
+ dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
+ dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det;
+ dst[2][0] = (src[1][0] * src[2][1] - src[1][1] * src[2][0]) / det;
+ dst[0][1] = (src[0][2] * src[2][1] - src[0][1] * src[2][2]) / det;
+ dst[1][1] = (src[0][0] * src[2][2] - src[0][2] * src[2][0]) / det;
+ dst[2][1] = (src[0][1] * src[2][0] - src[0][0] * src[2][1]) / det;
+ dst[0][2] = (src[0][1] * src[1][2] - src[0][2] * src[1][1]) / det;
+ dst[1][2] = (src[0][2] * src[1][0] - src[0][0] * src[1][2]) / det;
+ dst[2][2] = (src[0][0] * src[1][1] - src[0][1] * src[1][0]) / det;
+
+ return OK;
+}
+
+int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g)
+{
+ /* calculate offsets */
+ for (int i = 0; i < 3; i++) {
+ accel_offs[i] = (accel_ref[i * 2][i] + accel_ref[i * 2 + 1][i]) / 2;
+ }
+
+ /* fill matrix A for linear equations system*/
+ float mat_A[3][3];
+ memset(mat_A, 0, sizeof(mat_A));
+
+ for (int i = 0; i < 3; i++) {
+ for (int j = 0; j < 3; j++) {
+ float a = accel_ref[i * 2][j] - accel_offs[j];
+ mat_A[i][j] = a;
+ }
+ }
+
+ /* calculate inverse matrix for A */
+ float mat_A_inv[3][3];
+
+ if (mat_invert3(mat_A, mat_A_inv) != OK)
+ return ERROR;
+
+ /* copy results to accel_T */
+ for (int i = 0; i < 3; i++) {
+ for (int j = 0; j < 3; j++) {
+ /* simplify matrices mult because b has only one non-zero element == g at index i */
+ accel_T[j][i] = mat_A_inv[j][i] * g;
+ }
+ }
+
+ return OK;
+}
diff --git a/src/modules/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h
index a11cf93d3..1cf9c0977 100644
--- a/src/modules/commander/accelerometer_calibration.h
+++ b/src/modules/commander/accelerometer_calibration.h
@@ -1,16 +1,50 @@
-/*
- * accelerometer_calibration.h
+/****************************************************************************
*
- * Copyright (C) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 accelerometer_calibration.h
+ *
+ * Definition of accelerometer calibration.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef ACCELEROMETER_CALIBRATION_H_
#define ACCELEROMETER_CALIBRATION_H_
#include <stdint.h>
-#include <uORB/topics/vehicle_status.h>
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd);
+int do_accel_calibration(int mavlink_fd);
#endif /* ACCELEROMETER_CALIBRATION_H_ */
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
new file mode 100644
index 000000000..1809f9688
--- /dev/null
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -0,0 +1,154 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 airspeed_calibration.cpp
+ * Airspeed sensor calibration routine
+ */
+
+#include "airspeed_calibration.h"
+#include "calibration_messages.h"
+#include "commander_helper.h"
+
+#include <stdio.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <math.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_airspeed.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/differential_pressure.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+static const char *sensor_name = "dpress";
+
+int do_airspeed_calibration(int mavlink_fd)
+{
+ /* give directions */
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
+
+ const int calibration_count = 2500;
+
+ int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
+ struct differential_pressure_s diff_pres;
+
+ int calibration_counter = 0;
+ float diff_pres_offset = 0.0f;
+
+ /* Reset sensor parameters */
+ struct airspeed_scale airscale = {
+ 0.0f,
+ 1.0f,
+ };
+
+ bool paramreset_successful = false;
+ int fd = open(AIRSPEED_DEVICE_PATH, 0);
+ if (fd > 0) {
+ if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
+ paramreset_successful = true;
+ }
+ close(fd);
+ }
+
+ if (!paramreset_successful) {
+ warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ mavlink_log_critical(mavlink_fd, "could not reset dpress sensor");
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ return ERROR;
+ }
+
+ while (calibration_counter < calibration_count) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = diff_pres_sub;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+ diff_pres_offset += diff_pres.differential_pressure_pa;
+ calibration_counter++;
+
+ if (calibration_counter % (calibration_count / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+
+ } 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);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+ }
+
+ diff_pres_offset = diff_pres_offset / calibration_count;
+
+ if (isfinite(diff_pres_offset)) {
+
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
+ tune_neutral();
+ close(diff_pres_sub);
+ return OK;
+
+ } else {
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+}
diff --git a/src/modules/commander/airspeed_calibration.h b/src/modules/commander/airspeed_calibration.h
new file mode 100644
index 000000000..71c701fc2
--- /dev/null
+++ b/src/modules/commander/airspeed_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 gyro_calibration.h
+ * Airspeed sensor calibration routine
+ */
+
+#ifndef AIRSPEED_CALIBRATION_H_
+#define AIRSPEED_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_airspeed_calibration(int mavlink_fd);
+
+#endif /* AIRSPEED_CALIBRATION_H_ */
diff --git a/src/modules/commander/baro_calibration.cpp b/src/modules/commander/baro_calibration.cpp
new file mode 100644
index 000000000..3123c4087
--- /dev/null
+++ b/src/modules/commander/baro_calibration.cpp
@@ -0,0 +1,60 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 baro_calibration.cpp
+ * Barometer calibration routine
+ */
+
+#include "baro_calibration.h"
+
+#include <poll.h>
+#include <math.h>
+#include <fcntl.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_baro.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_baro_calibration(int mavlink_fd)
+{
+ // TODO implement this
+ return ERROR;
+}
diff --git a/src/modules/mathlib/math/generic/Matrix.cpp b/src/modules/commander/baro_calibration.h
index 21661622a..bc42bc6cf 100644
--- a/src/modules/mathlib/math/generic/Matrix.cpp
+++ b/src/modules/commander/baro_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 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
@@ -32,9 +32,15 @@
****************************************************************************/
/**
- * @file Matrix.cpp
- *
- * matrix code
+ * @file mag_calibration.h
+ * Barometer calibration routine
*/
-#include "Matrix.hpp"
+#ifndef BARO_CALIBRATION_H_
+#define BARO_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_baro_calibration(int mavlink_fd);
+
+#endif /* BARO_CALIBRATION_H_ */
diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h
new file mode 100644
index 000000000..fd8b8564d
--- /dev/null
+++ b/src/modules/commander/calibration_messages.h
@@ -0,0 +1,57 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 calibration_messages.h
+ *
+ * Common calibration messages.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef CALIBRATION_MESSAGES_H_
+#define CALIBRATION_MESSAGES_H_
+
+#define CAL_STARTED_MSG "%s calibration: started"
+#define CAL_DONE_MSG "%s calibration: done"
+#define CAL_FAILED_MSG "%s calibration: failed"
+#define CAL_PROGRESS_MSG "%s calibration: progress <%u>"
+
+#define CAL_FAILED_SENSOR_MSG "ERROR: failed reading sensor"
+#define CAL_FAILED_RESET_CAL_MSG "ERROR: failed to reset calibration"
+#define CAL_FAILED_APPLY_CAL_MSG "ERROR: failed to apply calibration"
+#define CAL_FAILED_SET_PARAMS_MSG "ERROR: failed to set parameters"
+#define CAL_FAILED_SAVE_PARAMS_MSG "ERROR: failed to save parameters"
+
+#endif /* CALIBRATION_MESSAGES_H_ */
diff --git a/src/modules/commander/calibration_routines.c b/src/modules/commander/calibration_routines.cpp
index a26938637..be38ea104 100644
--- a/src/modules/commander/calibration_routines.c
+++ b/src/modules/commander/calibration_routines.cpp
@@ -33,7 +33,7 @@
****************************************************************************/
/**
- * @file calibration_routines.c
+ * @file calibration_routines.cpp
* Calibration routines implementations.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
@@ -217,3 +217,4 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
return 0;
}
+
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
deleted file mode 100644
index 67f053e22..000000000
--- a/src/modules/commander/commander.c
+++ /dev/null
@@ -1,2078 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- *
- * 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 commander.c
- * Main system state machine implementation.
- *
- * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- *
- */
-
-#include "commander.h"
-
-#include <nuttx/config.h>
-#include <pthread.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <stdbool.h>
-#include <string.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <debug.h>
-#include <sys/prctl.h>
-#include <string.h>
-#include <drivers/drv_led.h>
-#include <drivers/drv_hrt.h>
-#include <drivers/drv_tone_alarm.h>
-#include "state_machine_helper.h"
-#include "systemlib/systemlib.h"
-#include <math.h>
-#include <poll.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/battery_status.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/offboard_control_setpoint.h>
-#include <uORB/topics/home_position.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <uORB/topics/vehicle_command.h>
-#include <uORB/topics/subsystem_info.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/differential_pressure.h>
-#include <mavlink/mavlink_log.h>
-
-#include <systemlib/param/param.h>
-#include <systemlib/systemlib.h>
-#include <systemlib/err.h>
-
-/* XXX MOVE CALIBRATION TO SENSORS APP THREAD */
-#include <drivers/drv_accel.h>
-#include <drivers/drv_gyro.h>
-#include <drivers/drv_mag.h>
-#include <drivers/drv_baro.h>
-
-#include "calibration_routines.h"
-#include "accelerometer_calibration.h"
-
-PARAM_DEFINE_INT32(SYS_FAILSAVE_LL, 0); /**< Go into low-level failsafe after 0 ms */
-//PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */
-PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
-PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
-PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
-
-#include <systemlib/cpuload.h>
-extern struct system_load_s system_load;
-
-/* Decouple update interval and hysteris counters, all depends on intervals */
-#define COMMANDER_MONITORING_INTERVAL 50000
-#define COMMANDER_MONITORING_LOOPSPERMSEC (1/(COMMANDER_MONITORING_INTERVAL/1000.0f))
-#define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-#define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-
-#define STICK_ON_OFF_LIMIT 0.75f
-#define STICK_THRUST_RANGE 1.0f
-#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
-#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-
-#define GPS_FIX_TYPE_2D 2
-#define GPS_FIX_TYPE_3D 3
-#define GPS_QUALITY_GOOD_HYSTERIS_TIME_MS 5000
-#define GPS_QUALITY_GOOD_COUNTER_LIMIT (GPS_QUALITY_GOOD_HYSTERIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-
-/* File descriptors */
-static int leds;
-static int buzzer;
-static int mavlink_fd;
-static bool commander_initialized = false;
-static struct vehicle_status_s current_status; /**< Main state machine */
-static orb_advert_t stat_pub;
-
-// static uint16_t nofix_counter = 0;
-// static uint16_t gotfix_counter = 0;
-
-static unsigned int failsafe_lowlevel_timeout_ms;
-
-static bool thread_should_exit = false; /**< daemon exit flag */
-static bool thread_running = false; /**< daemon status flag */
-static int daemon_task; /**< Handle of daemon task / thread */
-
-/* pthread loops */
-static void *orb_receive_loop(void *arg);
-
-__EXPORT int commander_main(int argc, char *argv[]);
-
-/**
- * Mainloop of commander.
- */
-int commander_thread_main(int argc, char *argv[]);
-
-static int buzzer_init(void);
-static void buzzer_deinit(void);
-static int led_init(void);
-static void led_deinit(void);
-static int led_toggle(int led);
-static int led_on(int led);
-static int led_off(int led);
-static void do_gyro_calibration(int status_pub, struct vehicle_status_s *status);
-static void do_mag_calibration(int status_pub, struct vehicle_status_s *status);
-static void do_rc_calibration(int status_pub, struct vehicle_status_s *status);
-static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd);
-
-int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state);
-
-
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-/**
- * Sort calibration values.
- *
- * Sorts the calibration values with bubble sort.
- *
- * @param a The array to sort
- * @param n The number of entries in the array
- */
-// static void cal_bsort(float a[], int n);
-
-static int buzzer_init()
-{
- buzzer = open("/dev/tone_alarm", O_WRONLY);
-
- if (buzzer < 0) {
- warnx("Buzzer: open fail\n");
- return ERROR;
- }
-
- return 0;
-}
-
-static void buzzer_deinit()
-{
- close(buzzer);
-}
-
-
-static int led_init()
-{
- leds = open(LED_DEVICE_PATH, 0);
-
- if (leds < 0) {
- warnx("LED: open fail\n");
- return ERROR;
- }
-
- if (ioctl(leds, LED_ON, LED_BLUE) || ioctl(leds, LED_ON, LED_AMBER)) {
- warnx("LED: ioctl fail\n");
- return ERROR;
- }
-
- return 0;
-}
-
-static void led_deinit()
-{
- close(leds);
-}
-
-static int led_toggle(int led)
-{
- static int last_blue = LED_ON;
- static int last_amber = LED_ON;
-
- if (led == LED_BLUE) last_blue = (last_blue == LED_ON) ? LED_OFF : LED_ON;
-
- if (led == LED_AMBER) last_amber = (last_amber == LED_ON) ? LED_OFF : LED_ON;
-
- return ioctl(leds, ((led == LED_BLUE) ? last_blue : last_amber), led);
-}
-
-static int led_on(int led)
-{
- return ioctl(leds, LED_ON, led);
-}
-
-static int led_off(int led)
-{
- return ioctl(leds, LED_OFF, led);
-}
-
-enum AUDIO_PATTERN {
- AUDIO_PATTERN_ERROR = 2,
- AUDIO_PATTERN_NOTIFY_POSITIVE = 3,
- AUDIO_PATTERN_NOTIFY_NEUTRAL = 4,
- AUDIO_PATTERN_NOTIFY_NEGATIVE = 5,
- AUDIO_PATTERN_NOTIFY_CHARGE = 6
-};
-
-int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state)
-{
-
- /* Trigger alarm if going into any error state */
- if (((new_state == SYSTEM_STATE_GROUND_ERROR) && (old_state != SYSTEM_STATE_GROUND_ERROR)) ||
- ((new_state == SYSTEM_STATE_MISSION_ABORT) && (old_state != SYSTEM_STATE_MISSION_ABORT))) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, AUDIO_PATTERN_ERROR);
- }
-
- /* Trigger neutral on arming / disarming */
- if (((new_state == SYSTEM_STATE_GROUND_READY) && (old_state != SYSTEM_STATE_GROUND_READY))) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, AUDIO_PATTERN_NOTIFY_NEUTRAL);
- }
-
- /* Trigger Tetris on being bored */
-
- return 0;
-}
-
-void tune_confirm(void)
-{
- ioctl(buzzer, TONE_SET_ALARM, 3);
-}
-
-void tune_error(void)
-{
- ioctl(buzzer, TONE_SET_ALARM, 4);
-}
-
-void do_rc_calibration(int status_pub, struct vehicle_status_s *status)
-{
- if (current_status.offboard_control_signal_lost) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
- return;
- }
-
- int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
- struct manual_control_setpoint_s sp;
- orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
-
- /* set parameters */
-
- float p = sp.roll;
- param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
- param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
- param_set(param_find("TRIM_YAW"), &p);
-
- /* store to permanent storage */
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
- }
-
- mavlink_log_info(mavlink_fd, "trim calibration done");
-}
-
-void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
-{
-
- /* set to mag calibration mode */
- status->flag_preflight_mag_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
- struct mag_report mag;
-
- /* 45 seconds */
- uint64_t calibration_interval = 45 * 1000 * 1000;
-
- /* maximum 2000 values */
- const unsigned int calibration_maxcount = 500;
- unsigned int calibration_counter = 0;
-
- /* limit update rate to get equally spaced measurements over time (in ms) */
- orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
-
- // XXX old cal
- // * FLT_MIN is not the most negative float number,
- // * but the smallest number by magnitude float can
- // * represent. Use -FLT_MAX to initialize the most
- // * negative number
-
- // float mag_max[3] = {-FLT_MAX, -FLT_MAX, -FLT_MAX};
- // float mag_min[3] = {FLT_MAX, FLT_MAX, FLT_MAX};
-
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
-
- /* erase old calibration */
- struct mag_scale mscale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
-
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set scale / offsets for mag");
- mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
- }
-
- /* calibrate range */
- if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
- warnx("failed to calibrate scale");
- }
-
- close(fd);
-
- /* calibrate offsets */
-
- // uint64_t calibration_start = hrt_absolute_time();
-
- uint64_t axis_deadline = hrt_absolute_time();
- uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
-
- const char axislabels[3] = { 'X', 'Y', 'Z'};
- int axis_index = -1;
-
- float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
-
- if (x == NULL || y == NULL || z == NULL) {
- warnx("mag cal failed: out of memory");
- mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
- warnx("x:%p y:%p z:%p\n", x, y, z);
- return;
- }
-
- tune_confirm();
- sleep(2);
- tune_confirm();
-
- while (hrt_absolute_time() < calibration_deadline &&
- calibration_counter < calibration_maxcount) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_mag, .events = POLLIN } };
-
- /* user guidance */
- if (hrt_absolute_time() >= axis_deadline &&
- axis_index < 3) {
-
- axis_index++;
-
- char buf[50];
- sprintf(buf, "Please rotate around %c", axislabels[axis_index]);
- mavlink_log_info(mavlink_fd, buf);
- tune_confirm();
-
- axis_deadline += calibration_interval / 3;
- }
-
- if (!(axis_index < 3)) {
- break;
- }
-
- // int axis_left = (int64_t)axis_deadline - (int64_t)hrt_absolute_time();
-
- // if ((axis_left / 1000) == 0 && axis_left > 0) {
- // char buf[50];
- // sprintf(buf, "[cmd] %d seconds left for axis %c", axis_left, axislabels[axis_index]);
- // mavlink_log_info(mavlink_fd, buf);
- // }
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
-
- x[calibration_counter] = mag.x;
- y[calibration_counter] = mag.y;
- z[calibration_counter] = mag.z;
-
- /* get min/max values */
-
- // if (mag.x < mag_min[0]) {
- // mag_min[0] = mag.x;
- // }
- // else if (mag.x > mag_max[0]) {
- // mag_max[0] = mag.x;
- // }
-
- // if (raw.magnetometer_ga[1] < mag_min[1]) {
- // mag_min[1] = raw.magnetometer_ga[1];
- // }
- // else if (raw.magnetometer_ga[1] > mag_max[1]) {
- // mag_max[1] = raw.magnetometer_ga[1];
- // }
-
- // if (raw.magnetometer_ga[2] < mag_min[2]) {
- // mag_min[2] = raw.magnetometer_ga[2];
- // }
- // else if (raw.magnetometer_ga[2] > mag_max[2]) {
- // mag_max[2] = raw.magnetometer_ga[2];
- // }
-
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "mag cal canceled (timed out)");
- break;
- }
- }
-
- float sphere_x;
- float sphere_y;
- float sphere_z;
- float sphere_radius;
-
- sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
-
- free(x);
- free(y);
- free(z);
-
- if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
-
- fd = open(MAG_DEVICE_PATH, 0);
-
- struct mag_scale mscale;
-
- if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to get scale / offsets for mag");
-
- mscale.x_offset = sphere_x;
- mscale.y_offset = sphere_y;
- mscale.z_offset = sphere_z;
-
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to set scale / offsets for mag");
-
- close(fd);
-
- /* announce and set new offset */
-
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
- warnx("Setting X mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
- warnx("Setting Y mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
- warnx("Setting Z mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
- warnx("Setting X mag scale failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
- warnx("Setting Y mag scale failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
- warnx("Setting Z mag scale failed!\n");
- }
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- mavlink_log_info(mavlink_fd, "FAILED storing calibration");
- }
-
- warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
- (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
- (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
-
- char buf[52];
- sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
- (double)mscale.y_offset, (double)mscale.z_offset);
- mavlink_log_info(mavlink_fd, buf);
-
- sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
- (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, buf);
-
- mavlink_log_info(mavlink_fd, "mag calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
- }
-
- /* disable calibration mode */
- status->flag_preflight_mag_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- close(sub_mag);
-}
-
-void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
-{
- /* set to gyro calibration mode */
- status->flag_preflight_gyro_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- const int calibration_count = 5000;
-
- int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s raw;
-
- int calibration_counter = 0;
- float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
-
- /* set offsets to zero */
- int fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
-
- while (calibration_counter < calibration_count) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- gyro_offset[0] += raw.gyro_rad_s[0];
- gyro_offset[1] += raw.gyro_rad_s[1];
- gyro_offset[2] += raw.gyro_rad_s[2];
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
- return;
- }
- }
-
- gyro_offset[0] = gyro_offset[0] / calibration_count;
- gyro_offset[1] = gyro_offset[1] / calibration_count;
- gyro_offset[2] = gyro_offset[2] / calibration_count;
-
- /* exit gyro calibration mode */
- status->flag_preflight_gyro_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
-
- if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
- || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
- || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
- }
-
- /* set offsets to actual value */
- fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- 1.0f,
- gyro_offset[1],
- 1.0f,
- gyro_offset[2],
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- // char buf[50];
- // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
- // mavlink_log_info(mavlink_fd, buf);
- mavlink_log_info(mavlink_fd, "gyro calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
- }
-
- close(sub_sensor_combined);
-}
-
-void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status)
-{
- /* announce change */
-
- mavlink_log_info(mavlink_fd, "keep it still");
- /* set to accel calibration mode */
- status->flag_preflight_airspeed_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- const int calibration_count = 2500;
-
- int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
- struct differential_pressure_s diff_pres;
-
- int calibration_counter = 0;
- float diff_pres_offset = 0.0f;
-
- while (calibration_counter < calibration_count) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = diff_pres_sub, .events = POLLIN } };
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- diff_pres_offset += diff_pres.differential_pressure_pa;
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "airspeed calibration aborted");
- return;
- }
- }
-
- diff_pres_offset = diff_pres_offset / calibration_count;
-
- if (isfinite(diff_pres_offset)) {
-
- if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
- mavlink_log_critical(mavlink_fd, "Setting offs failed!");
- }
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- //char buf[50];
- //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]);
- //mavlink_log_info(mavlink_fd, buf);
- mavlink_log_info(mavlink_fd, "airspeed calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "airspeed calibration FAILED (NaN)");
- }
-
- /* exit airspeed calibration mode */
- status->flag_preflight_airspeed_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- close(diff_pres_sub);
-}
-
-
-
-void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_status, struct vehicle_command_s *cmd)
-{
- /* result of the command */
- uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
-
- /* announce command handling */
- tune_confirm();
-
-
- /* supported command handling start */
-
- /* request to set different system mode */
- switch (cmd->command) {
- case VEHICLE_CMD_DO_SET_MODE: {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, (uint8_t)cmd->param1)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- break;
-
- case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- /* request to arm */
- if ((int)cmd->param1 == 1) {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- /* request to disarm */
-
- } else if ((int)cmd->param1 == 0) {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- }
- break;
-
- /* request for an autopilot reboot */
- case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN: {
- if ((int)cmd->param1 == 1) {
- if (OK == do_state_update(status_pub, current_vehicle_status, mavlink_fd, SYSTEM_STATE_REBOOT)) {
- /* SPECIAL CASE: SYSTEM WILL NEVER RETURN HERE */
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- /* system may return here */
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- }
- break;
-
-// /* request to land */
-// case VEHICLE_CMD_NAV_LAND:
-// {
-// //TODO: add check if landing possible
-// //TODO: add landing maneuver
-//
-// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_ARMED)) {
-// result = VEHICLE_CMD_RESULT_ACCEPTED;
-// } }
-// break;
-//
-// /* request to takeoff */
-// case VEHICLE_CMD_NAV_TAKEOFF:
-// {
-// //TODO: add check if takeoff possible
-// //TODO: add takeoff maneuver
-//
-// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_AUTO)) {
-// result = VEHICLE_CMD_RESULT_ACCEPTED;
-// }
-// }
-// break;
-//
- /* preflight calibration */
- case VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
- bool handled = false;
-
- /* gyro calibration */
- if ((int)(cmd->param1) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting gyro cal");
- tune_confirm();
- do_gyro_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished gyro cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING gyro cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* magnetometer calibration */
- if ((int)(cmd->param2) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting mag cal");
- tune_confirm();
- do_mag_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished mag cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING mag cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* zero-altitude pressure calibration */
- if ((int)(cmd->param3) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "zero altitude cal. not implemented");
- tune_confirm();
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING altitude calibration");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* trim calibration */
- if ((int)(cmd->param4) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting trim cal");
- tune_confirm();
- do_rc_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished trim cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING trim cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* accel calibration */
- if ((int)(cmd->param5) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "CMD starting accel cal");
- tune_confirm();
- do_accel_calibration(status_pub, &current_status, mavlink_fd);
- tune_confirm();
- mavlink_log_info(mavlink_fd, "CMD finished accel cal");
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING accel cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* airspeed calibration */
- if ((int)(cmd->param6) == 1) { //xxx: this is not defined by the mavlink protocol
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "CMD starting airspeed cal");
- tune_confirm();
- do_airspeed_calibration(status_pub, &current_status);
- tune_confirm();
- mavlink_log_info(mavlink_fd, "CMD finished airspeed cal");
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING airspeed cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* none found */
- if (!handled) {
- //warnx("refusing unsupported calibration request\n");
- mavlink_log_critical(mavlink_fd, "CMD refusing unsup. calib. request");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- }
- }
- break;
-
- case VEHICLE_CMD_PREFLIGHT_STORAGE: {
- if (current_status.flag_system_armed &&
- ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_OCTOROTOR))) {
- /* do not perform expensive memory tasks on multirotors in flight */
- // XXX this is over-safe, as soon as cmd is in low prio thread this can be allowed
- mavlink_log_info(mavlink_fd, "REJECTING save cmd while multicopter armed");
-
- } else {
-
- // XXX move this to LOW PRIO THREAD of commander app
- /* Read all parameters from EEPROM to RAM */
-
- if (((int)(cmd->param1)) == 0) {
-
- /* read all parameters from EEPROM to RAM */
- int read_ret = param_load_default();
-
- if (read_ret == OK) {
- //warnx("[mavlink pm] Loaded EEPROM params in RAM\n");
- mavlink_log_info(mavlink_fd, "OK loading params from");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else if (read_ret == 1) {
- mavlink_log_info(mavlink_fd, "OK no changes in");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- if (read_ret < -1) {
- mavlink_log_info(mavlink_fd, "ERR loading params from");
- mavlink_log_info(mavlink_fd, param_get_default_file());
-
- } else {
- mavlink_log_info(mavlink_fd, "ERR no param file named");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- }
-
- result = VEHICLE_CMD_RESULT_FAILED;
- }
-
- } else if (((int)(cmd->param1)) == 1) {
-
- /* write all parameters from RAM to EEPROM */
- int write_ret = param_save_default();
-
- if (write_ret == OK) {
- mavlink_log_info(mavlink_fd, "OK saved param file");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- if (write_ret < -1) {
- mavlink_log_info(mavlink_fd, "ERR params file does not exit:");
- mavlink_log_info(mavlink_fd, param_get_default_file());
-
- } else {
- mavlink_log_info(mavlink_fd, "ERR writing params to");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- }
-
- result = VEHICLE_CMD_RESULT_FAILED;
- }
-
- } else {
- mavlink_log_info(mavlink_fd, "[pm] refusing unsupp. STOR request");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- }
- }
- }
- break;
-
- default: {
- mavlink_log_critical(mavlink_fd, "[cmd] refusing unsupported command");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- /* announce command rejection */
- ioctl(buzzer, TONE_SET_ALARM, 4);
- }
- break;
- }
-
- /* supported command handling stop */
- if (result == VEHICLE_CMD_RESULT_FAILED ||
- result == VEHICLE_CMD_RESULT_DENIED ||
- result == VEHICLE_CMD_RESULT_UNSUPPORTED) {
- ioctl(buzzer, TONE_SET_ALARM, 5);
-
- } else if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
- tune_confirm();
- }
-
- /* send any requested ACKs */
- if (cmd->confirmation > 0) {
- /* send acknowledge command */
- // XXX TODO
- }
-
-}
-
-static void *orb_receive_loop(void *arg) //handles status information coming from subsystems (present, enabled, health), these values do not indicate the quality (variance) of the signal
-{
- /* Set thread name */
- prctl(PR_SET_NAME, "commander orb rcv", getpid());
-
- /* Subscribe to command topic */
- int subsys_sub = orb_subscribe(ORB_ID(subsystem_info));
- struct subsystem_info_s info;
-
- struct vehicle_status_s *vstatus = (struct vehicle_status_s *)arg;
-
- while (!thread_should_exit) {
- struct pollfd fds[1] = { { .fd = subsys_sub, .events = POLLIN } };
-
- if (poll(fds, 1, 5000) == 0) {
- /* timeout, but this is no problem, silently ignore */
- } else {
- /* got command */
- orb_copy(ORB_ID(subsystem_info), subsys_sub, &info);
-
- warnx("Subsys changed: %d\n", (int)info.subsystem_type);
-
- /* mark / unmark as present */
- if (info.present) {
- vstatus->onboard_control_sensors_present |= info.subsystem_type;
-
- } else {
- vstatus->onboard_control_sensors_present &= ~info.subsystem_type;
- }
-
- /* mark / unmark as enabled */
- if (info.enabled) {
- vstatus->onboard_control_sensors_enabled |= info.subsystem_type;
-
- } else {
- vstatus->onboard_control_sensors_enabled &= ~info.subsystem_type;
- }
-
- /* mark / unmark as ok */
- if (info.ok) {
- vstatus->onboard_control_sensors_health |= info.subsystem_type;
-
- } else {
- vstatus->onboard_control_sensors_health &= ~info.subsystem_type;
- }
- }
- }
-
- close(subsys_sub);
-
- return NULL;
-}
-
-/*
- * Provides a coarse estimate of remaining battery power.
- *
- * The estimate is very basic and based on decharging voltage curves.
- *
- * @return the estimated remaining capacity in 0..1
- */
-float battery_remaining_estimate_voltage(float voltage);
-
-PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.2f);
-PARAM_DEFINE_FLOAT(BAT_V_FULL, 4.05f);
-PARAM_DEFINE_FLOAT(BAT_N_CELLS, 3);
-
-float battery_remaining_estimate_voltage(float voltage)
-{
- float ret = 0;
- static param_t bat_volt_empty;
- static param_t bat_volt_full;
- static param_t bat_n_cells;
- static bool initialized = false;
- static unsigned int counter = 0;
- static float ncells = 3;
- // XXX change cells to int (and param to INT32)
-
- if (!initialized) {
- bat_volt_empty = param_find("BAT_V_EMPTY");
- bat_volt_full = param_find("BAT_V_FULL");
- bat_n_cells = param_find("BAT_N_CELLS");
- initialized = true;
- }
-
- static float chemistry_voltage_empty = 3.2f;
- static float chemistry_voltage_full = 4.05f;
-
- if (counter % 100 == 0) {
- param_get(bat_volt_empty, &chemistry_voltage_empty);
- param_get(bat_volt_full, &chemistry_voltage_full);
- param_get(bat_n_cells, &ncells);
- }
-
- counter++;
-
- ret = (voltage - ncells * chemistry_voltage_empty) / (ncells * (chemistry_voltage_full - chemistry_voltage_empty));
-
- /* limit to sane values */
- ret = (ret < 0) ? 0 : ret;
- ret = (ret > 1) ? 1 : ret;
- return ret;
-}
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
- exit(1);
-}
-
-/**
- * The daemon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int commander_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- warnx("commander already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- daemon_task = task_spawn_cmd("commander",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 40,
- 3000,
- commander_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- warnx("\tcommander is running\n");
-
- } else {
- warnx("\tcommander not started\n");
- }
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-int commander_thread_main(int argc, char *argv[])
-{
- /* not yet initialized */
- commander_initialized = false;
- bool home_position_set = false;
-
- /* set parameters */
- failsafe_lowlevel_timeout_ms = 0;
- param_get(param_find("SYS_FAILSAVE_LL"), &failsafe_lowlevel_timeout_ms);
-
- param_t _param_sys_type = param_find("MAV_TYPE");
- param_t _param_system_id = param_find("MAV_SYS_ID");
- param_t _param_component_id = param_find("MAV_COMP_ID");
-
- /* welcome user */
- warnx("I am in command now!\n");
-
- /* pthreads for command and subsystem info handling */
- // pthread_t command_handling_thread;
- pthread_t subsystem_info_thread;
-
- /* initialize */
- if (led_init() != 0) {
- warnx("ERROR: Failed to initialize leds\n");
- }
-
- if (buzzer_init() != 0) {
- warnx("ERROR: Failed to initialize buzzer\n");
- }
-
- mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
- if (mavlink_fd < 0) {
- warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n");
- }
-
- /* make sure we are in preflight state */
- memset(&current_status, 0, sizeof(current_status));
- current_status.state_machine = SYSTEM_STATE_PREFLIGHT;
- current_status.flag_system_armed = false;
- /* neither manual nor offboard control commands have been received */
- current_status.offboard_control_signal_found_once = false;
- current_status.rc_signal_found_once = false;
- /* mark all signals lost as long as they haven't been found */
- current_status.rc_signal_lost = true;
- current_status.offboard_control_signal_lost = true;
- /* allow manual override initially */
- current_status.flag_external_manual_override_ok = true;
- /* flag position info as bad, do not allow auto mode */
- current_status.flag_vector_flight_mode_ok = false;
- /* set battery warning flag */
- current_status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
-
- /* advertise to ORB */
- stat_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
- /* publish current state machine */
- state_machine_publish(stat_pub, &current_status, mavlink_fd);
-
- /* home position */
- orb_advert_t home_pub = -1;
- struct home_position_s home;
- memset(&home, 0, sizeof(home));
-
- if (stat_pub < 0) {
- warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
- warnx("exiting.");
- exit(ERROR);
- }
-
- mavlink_log_info(mavlink_fd, "system is running");
-
- /* create pthreads */
- pthread_attr_t subsystem_info_attr;
- pthread_attr_init(&subsystem_info_attr);
- pthread_attr_setstacksize(&subsystem_info_attr, 2048);
- pthread_create(&subsystem_info_thread, &subsystem_info_attr, orb_receive_loop, &current_status);
-
- /* Start monitoring loop */
- uint16_t counter = 0;
- uint8_t flight_env;
-
- /* Initialize to 0.0V */
- float battery_voltage = 0.0f;
- bool battery_voltage_valid = false;
- bool low_battery_voltage_actions_done = false;
- bool critical_battery_voltage_actions_done = false;
- uint8_t low_voltage_counter = 0;
- uint16_t critical_voltage_counter = 0;
- int16_t mode_switch_rc_value;
- float bat_remain = 1.0f;
-
- uint16_t stick_off_counter = 0;
- uint16_t stick_on_counter = 0;
-
- /* Subscribe to manual control data */
- int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- struct manual_control_setpoint_s sp_man;
- memset(&sp_man, 0, sizeof(sp_man));
-
- /* Subscribe to offboard control data */
- int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- struct offboard_control_setpoint_s sp_offboard;
- memset(&sp_offboard, 0, sizeof(sp_offboard));
-
- int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- struct vehicle_global_position_s global_position;
- memset(&global_position, 0, sizeof(global_position));
- uint64_t last_global_position_time = 0;
-
- int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
- struct vehicle_local_position_s local_position;
- memset(&local_position, 0, sizeof(local_position));
- uint64_t last_local_position_time = 0;
-
- /*
- * The home position is set based on GPS only, to prevent a dependency between
- * position estimator and commander. RAW GPS is more than good enough for a
- * non-flying vehicle.
- */
- int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- struct vehicle_gps_position_s gps_position;
- memset(&gps_position, 0, sizeof(gps_position));
-
- int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s sensors;
- memset(&sensors, 0, sizeof(sensors));
-
- int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
- struct differential_pressure_s diff_pres;
- memset(&diff_pres, 0, sizeof(diff_pres));
- uint64_t last_diff_pres_time = 0;
-
- /* Subscribe to command topic */
- int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
- struct vehicle_command_s cmd;
- memset(&cmd, 0, sizeof(cmd));
-
- /* Subscribe to parameters changed topic */
- int param_changed_sub = orb_subscribe(ORB_ID(parameter_update));
- struct parameter_update_s param_changed;
- memset(&param_changed, 0, sizeof(param_changed));
-
- /* subscribe to battery topic */
- int battery_sub = orb_subscribe(ORB_ID(battery_status));
- struct battery_status_s battery;
- memset(&battery, 0, sizeof(battery));
- battery.voltage_v = 0.0f;
-
- // uint8_t vehicle_state_previous = current_status.state_machine;
- float voltage_previous = 0.0f;
-
- uint64_t last_idle_time = 0;
-
- /* now initialized */
- commander_initialized = true;
- thread_running = true;
-
- uint64_t start_time = hrt_absolute_time();
- uint64_t failsave_ll_start_time = 0;
-
- bool state_changed = true;
- bool param_init_forced = true;
-
- while (!thread_should_exit) {
-
- /* Get current values */
- bool new_data;
- orb_check(sp_man_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(manual_control_setpoint), sp_man_sub, &sp_man);
- }
-
- orb_check(sp_offboard_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
- }
-
- orb_check(sensor_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
- }
-
- orb_check(diff_pres_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- last_diff_pres_time = diff_pres.timestamp;
- }
-
- orb_check(cmd_sub, &new_data);
-
- if (new_data) {
- /* got command */
- orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
-
- /* handle it */
- handle_command(stat_pub, &current_status, &cmd);
- }
-
- /* update parameters */
- orb_check(param_changed_sub, &new_data);
-
- if (new_data || param_init_forced) {
- param_init_forced = false;
- /* parameters changed */
- orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
-
-
- /* update parameters */
- if (!current_status.flag_system_armed) {
- if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
- warnx("failed setting new system type");
- }
-
- /* disable manual override for all systems that rely on electronic stabilization */
- if (current_status.system_type == VEHICLE_TYPE_QUADROTOR ||
- current_status.system_type == VEHICLE_TYPE_HEXAROTOR ||
- current_status.system_type == VEHICLE_TYPE_OCTOROTOR) {
- current_status.flag_external_manual_override_ok = false;
-
- } else {
- current_status.flag_external_manual_override_ok = true;
- }
-
- /* check and update system / component ID */
- param_get(_param_system_id, &(current_status.system_id));
- param_get(_param_component_id, &(current_status.component_id));
-
- }
- }
-
- /* update global position estimate */
- orb_check(global_position_sub, &new_data);
-
- if (new_data) {
- /* position changed */
- orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_position);
- last_global_position_time = global_position.timestamp;
- }
-
- /* update local position estimate */
- orb_check(local_position_sub, &new_data);
-
- if (new_data) {
- /* position changed */
- orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
- last_local_position_time = local_position.timestamp;
- }
-
- /* update battery status */
- orb_check(battery_sub, &new_data);
- if (new_data) {
- orb_copy(ORB_ID(battery_status), battery_sub, &battery);
- battery_voltage = battery.voltage_v;
- battery_voltage_valid = true;
-
- /*
- * Only update battery voltage estimate if system has
- * been running for two and a half seconds.
- */
- if (hrt_absolute_time() - start_time > 2500000) {
- bat_remain = battery_remaining_estimate_voltage(battery_voltage);
- }
- }
-
- /* Slow but important 8 Hz checks */
- if (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 8) == 0) {
- /* toggle activity (blue) led at 1 Hz in standby, 10 Hz in armed mode */
- if ((current_status.state_machine == SYSTEM_STATE_GROUND_READY ||
- current_status.state_machine == SYSTEM_STATE_AUTO ||
- current_status.state_machine == SYSTEM_STATE_MANUAL)) {
- /* armed, solid */
- led_on(LED_AMBER);
-
- } else if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- /* not armed */
- led_toggle(LED_AMBER);
- }
-
- if (hrt_absolute_time() - gps_position.timestamp_position < 2000000) {
-
- /* toggle GPS (blue) led at 1 Hz if GPS present but no lock, make is solid once locked */
- if ((hrt_absolute_time() - gps_position.timestamp_position < 2000000)
- && (gps_position.fix_type == GPS_FIX_TYPE_3D)) {
- /* GPS lock */
- led_on(LED_BLUE);
-
- } else if ((counter + 4) % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- /* no GPS lock, but GPS module is aquiring lock */
- led_toggle(LED_BLUE);
- }
-
- } else {
- /* no GPS info, don't light the blue led */
- led_off(LED_BLUE);
- }
-
- /* toggle GPS led at 5 Hz in HIL mode */
- if (current_status.flag_hil_enabled) {
- /* hil enabled */
- led_toggle(LED_BLUE);
-
- } else if (bat_remain < 0.3f && (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT)) {
- /* toggle arming (red) at 5 Hz on low battery or error */
- led_toggle(LED_AMBER);
-
- } else {
- // /* Constant error indication in standby mode without GPS */
- // if (!current_status.gps_valid) {
- // led_on(LED_AMBER);
-
- // } else {
- // led_off(LED_AMBER);
- // }
- }
-
- if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- /* compute system load */
- uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
-
- if (last_idle_time > 0)
- current_status.load = 1000 - (interval_runtime / 1000); //system load is time spent in non-idle
-
- last_idle_time = system_load.tasks[0].total_runtime;
- }
- }
-
- // // XXX Export patterns and threshold to parameters
- /* Trigger audio event for low battery */
- if (bat_remain < 0.1f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 4) == 0)) {
- /* For less than 10%, start be really annoying at 5 Hz */
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, 3);
-
- } else if (bat_remain < 0.1f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 4) == 2)) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
-
- } else if (bat_remain < 0.2f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 2) == 0)) {
- /* For less than 20%, start be slightly annoying at 1 Hz */
- ioctl(buzzer, TONE_SET_ALARM, 0);
- tune_confirm();
-
- } else if (bat_remain < 0.2f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 2) == 2)) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- }
-
- /* Check battery voltage */
- /* write to sys_status */
- if (battery_voltage_valid) {
- current_status.voltage_battery = battery_voltage;
-
- } else {
- current_status.voltage_battery = 0.0f;
- }
-
- /* if battery voltage is getting lower, warn using buzzer, etc. */
- if (battery_voltage_valid && (bat_remain < 0.15f /* XXX MAGIC NUMBER */) && (false == low_battery_voltage_actions_done)) { //TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS
-
- if (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT) {
- low_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "[cmd] WARNING! LOW BATTERY!");
- current_status.battery_warning = VEHICLE_BATTERY_WARNING_WARNING;
- }
-
- low_voltage_counter++;
- }
-
- /* Critical, this is rather an emergency, kill signal to sdlog and change state machine */
- else if (battery_voltage_valid && (bat_remain < 0.1f /* XXX MAGIC NUMBER */) && (false == critical_battery_voltage_actions_done && true == low_battery_voltage_actions_done)) {
- if (critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT) {
- critical_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY! CRITICAL BATTERY!");
- current_status.battery_warning = VEHICLE_BATTERY_WARNING_ALERT;
- state_machine_emergency(stat_pub, &current_status, mavlink_fd);
- }
-
- critical_voltage_counter++;
-
- } else {
- low_voltage_counter = 0;
- critical_voltage_counter = 0;
- }
-
- /* End battery voltage check */
-
-
- /*
- * Check for valid position information.
- *
- * If the system has a valid position source from an onboard
- * position estimator, it is safe to operate it autonomously.
- * The flag_vector_flight_mode_ok flag indicates that a minimum
- * set of position measurements is available.
- */
-
- /* store current state to reason later about a state change */
- bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
- bool global_pos_valid = current_status.flag_global_position_valid;
- bool local_pos_valid = current_status.flag_local_position_valid;
- bool airspeed_valid = current_status.flag_airspeed_valid;
-
- /* check for global or local position updates, set a timeout of 2s */
- if (hrt_absolute_time() - last_global_position_time < 2000000) {
- current_status.flag_global_position_valid = true;
- // XXX check for controller status and home position as well
-
- } else {
- current_status.flag_global_position_valid = false;
- }
-
- if (hrt_absolute_time() - last_local_position_time < 2000000) {
- current_status.flag_local_position_valid = true;
- // XXX check for controller status and home position as well
-
- } else {
- current_status.flag_local_position_valid = false;
- }
-
- /* Check for valid airspeed/differential pressure measurements */
- if (hrt_absolute_time() - last_diff_pres_time < 2000000) {
- current_status.flag_airspeed_valid = true;
-
- } else {
- current_status.flag_airspeed_valid = false;
- }
-
- /*
- * Consolidate global position and local position valid flags
- * for vector flight mode.
- */
- if (current_status.flag_local_position_valid ||
- current_status.flag_global_position_valid) {
- current_status.flag_vector_flight_mode_ok = true;
-
- } else {
- current_status.flag_vector_flight_mode_ok = false;
- }
-
- /* consolidate state change, flag as changed if required */
- if (vector_flight_mode_ok != current_status.flag_vector_flight_mode_ok ||
- global_pos_valid != current_status.flag_global_position_valid ||
- local_pos_valid != current_status.flag_local_position_valid ||
- airspeed_valid != current_status.flag_airspeed_valid) {
- state_changed = true;
- }
-
- /*
- * Mark the position of the first position lock as return to launch (RTL)
- * position. The MAV will return here on command or emergency.
- *
- * Conditions:
- *
- * 1) The system aquired position lock just now
- * 2) The system has not aquired position lock before
- * 3) The system is not armed (on the ground)
- */
- if (!current_status.flag_valid_launch_position &&
- !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok &&
- !current_status.flag_system_armed) {
- /* first time a valid position, store it and emit it */
-
- // XXX implement storage and publication of RTL position
- current_status.flag_valid_launch_position = true;
- current_status.flag_auto_flight_mode_ok = true;
- state_changed = true;
- }
-
- if (orb_check(ORB_ID(vehicle_gps_position), &new_data)) {
-
- orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
-
- /* check for first, long-term and valid GPS lock -> set home position */
- float hdop_m = gps_position.eph_m;
- float vdop_m = gps_position.epv_m;
-
- /* check if gps fix is ok */
- // XXX magic number
- float hdop_threshold_m = 4.0f;
- float vdop_threshold_m = 8.0f;
-
- /*
- * If horizontal dilution of precision (hdop / eph)
- * and vertical diluation of precision (vdop / epv)
- * are below a certain threshold (e.g. 4 m), AND
- * home position is not yet set AND the last GPS
- * GPS measurement is not older than two seconds AND
- * the system is currently not armed, set home
- * position to the current position.
- */
-
- if (gps_position.fix_type == GPS_FIX_TYPE_3D
- && (hdop_m < hdop_threshold_m)
- && (vdop_m < vdop_threshold_m)
- && !home_position_set
- && (hrt_absolute_time() - gps_position.timestamp_position < 2000000)
- && !current_status.flag_system_armed) {
- warnx("setting home position");
-
- /* copy position data to uORB home message, store it locally as well */
- home.lat = gps_position.lat;
- home.lon = gps_position.lon;
- home.alt = gps_position.alt;
-
- home.eph_m = gps_position.eph_m;
- home.epv_m = gps_position.epv_m;
-
- home.s_variance_m_s = gps_position.s_variance_m_s;
- home.p_variance_m = gps_position.p_variance_m;
-
- /* announce new home position */
- if (home_pub > 0) {
- orb_publish(ORB_ID(home_position), home_pub, &home);
- } else {
- home_pub = orb_advertise(ORB_ID(home_position), &home);
- }
-
- /* mark home position as set */
- home_position_set = true;
- tune_confirm();
- }
- }
-
- /* ignore RC signals if in offboard control mode */
- if (!current_status.offboard_control_signal_found_once && sp_man.timestamp != 0) {
- /* Start RC state check */
-
- if ((hrt_absolute_time() - sp_man.timestamp) < 100000) {
-
- // /*
- // * Check if manual control modes have to be switched
- // */
- // if (!isfinite(sp_man.manual_mode_switch)) {
- // warnx("man mode sw not finite\n");
-
- // /* this switch is not properly mapped, set default */
- // if ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- // /* assuming a rotary wing, fall back to SAS */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
- // } else {
-
- // /* assuming a fixed wing, fall back to direct pass-through */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = false;
- // }
-
- // } else if (sp_man.manual_mode_switch < -STICK_ON_OFF_LIMIT) {
-
- // /* bottom stick position, set direct mode for vehicles supporting it */
- // if ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- // /* assuming a rotary wing, fall back to SAS */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
- // } else {
-
- // /* assuming a fixed wing, set to direct pass-through as requested */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = false;
- // }
-
- // } else if (sp_man.manual_mode_switch > STICK_ON_OFF_LIMIT) {
-
- // /* top stick position, set SAS for all vehicle types */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
-
- // } else {
- // /* center stick position, set rate control */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = true;
- // }
-
- // warnx("man ctrl mode: %d\n", (int)current_status.manual_control_mode);
-
- /*
- * Check if manual stability control modes have to be switched
- */
- if (!isfinite(sp_man.manual_sas_switch)) {
-
- /* this switch is not properly mapped, set default */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
-
- } else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) {
-
- /* bottom stick position, set altitude hold */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
-
- } else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) {
-
- /* top stick position */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_SIMPLE;
-
- } else {
- /* center stick position, set default */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
- }
-
- /*
- * Check if left stick is in lower left position --> switch to standby state.
- * Do this only for multirotors, not for fixed wing aircraft.
- */
- if (((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)
- ) &&
- ((sp_man.yaw < -STICK_ON_OFF_LIMIT)) &&
- (sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) {
- if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
- stick_on_counter = 0;
-
- } else {
- stick_off_counter++;
- stick_on_counter = 0;
- }
- }
-
- /* check if left stick is in lower right position --> arm */
- if (sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.2f) {
- if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
- stick_on_counter = 0;
-
- } else {
- stick_on_counter++;
- stick_off_counter = 0;
- }
- }
-
- /* check manual override switch - switch to manual or auto mode */
- if (sp_man.manual_override_switch > STICK_ON_OFF_LIMIT) {
- /* enable manual override */
- update_state_machine_mode_manual(stat_pub, &current_status, mavlink_fd);
-
- } else if (sp_man.manual_override_switch < -STICK_ON_OFF_LIMIT) {
- // /* check auto mode switch for correct mode */
- // if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) {
- // /* enable guided mode */
- // update_state_machine_mode_guided(stat_pub, &current_status, mavlink_fd);
-
- // } else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) {
- // XXX hardcode to auto for now
- update_state_machine_mode_auto(stat_pub, &current_status, mavlink_fd);
-
- // }
-
- } else {
- /* center stick position, set SAS for all vehicle types */
- update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
- }
-
- /* handle the case where RC signal was regained */
- if (!current_status.rc_signal_found_once) {
- current_status.rc_signal_found_once = true;
- mavlink_log_critical(mavlink_fd, "DETECTED RC SIGNAL FIRST TIME.");
-
- } else {
- if (current_status.rc_signal_lost) mavlink_log_critical(mavlink_fd, "[cmd] RECOVERY - RC SIGNAL GAINED!");
- }
-
- current_status.rc_signal_cutting_off = false;
- current_status.rc_signal_lost = false;
- current_status.rc_signal_lost_interval = 0;
-
- } else {
- static uint64_t last_print_time = 0;
-
- /* print error message for first RC glitch and then every 5 s / 5000 ms) */
- if (!current_status.rc_signal_cutting_off || ((hrt_absolute_time() - last_print_time) > 5000000)) {
- /* only complain if the offboard control is NOT active */
- current_status.rc_signal_cutting_off = true;
- mavlink_log_critical(mavlink_fd, "CRITICAL - NO REMOTE SIGNAL!");
- last_print_time = hrt_absolute_time();
- }
-
- /* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
- current_status.rc_signal_lost_interval = hrt_absolute_time() - sp_man.timestamp;
-
- /* if the RC signal is gone for a full second, consider it lost */
- if (current_status.rc_signal_lost_interval > 1000000) {
- current_status.rc_signal_lost = true;
- current_status.failsave_lowlevel = true;
- state_changed = true;
- }
-
- // if (hrt_absolute_time() - current_status.failsave_ll_start_time > failsafe_lowlevel_timeout_ms*1000) {
- // publish_armed_status(&current_status);
- // }
- }
- }
-
-
-
-
- /* End mode switch */
-
- /* END RC state check */
-
-
- /* State machine update for offboard control */
- if (!current_status.rc_signal_found_once && sp_offboard.timestamp != 0) {
- if ((hrt_absolute_time() - sp_offboard.timestamp) < 5000000) {
-
- /* decide about attitude control flag, enable in att/pos/vel */
- bool attitude_ctrl_enabled = (sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE ||
- sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY ||
- sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION);
-
- /* decide about rate control flag, enable it always XXX (for now) */
- bool rates_ctrl_enabled = true;
-
- /* set up control mode */
- if (current_status.flag_control_attitude_enabled != attitude_ctrl_enabled) {
- current_status.flag_control_attitude_enabled = attitude_ctrl_enabled;
- state_changed = true;
- }
-
- if (current_status.flag_control_rates_enabled != rates_ctrl_enabled) {
- current_status.flag_control_rates_enabled = rates_ctrl_enabled;
- state_changed = true;
- }
-
- /* handle the case where offboard control signal was regained */
- if (!current_status.offboard_control_signal_found_once) {
- current_status.offboard_control_signal_found_once = true;
- /* enable offboard control, disable manual input */
- current_status.flag_control_manual_enabled = false;
- current_status.flag_control_offboard_enabled = true;
- state_changed = true;
- tune_confirm();
-
- mavlink_log_critical(mavlink_fd, "DETECTED OFFBOARD SIGNAL FIRST");
-
- } else {
- if (current_status.offboard_control_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RECOVERY OFFBOARD CONTROL");
- state_changed = true;
- tune_confirm();
- }
- }
-
- current_status.offboard_control_signal_weak = false;
- current_status.offboard_control_signal_lost = false;
- current_status.offboard_control_signal_lost_interval = 0;
-
- /* arm / disarm on request */
- if (sp_offboard.armed && !current_status.flag_system_armed) {
- update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
- /* switch to stabilized mode = takeoff */
- update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
-
- } else if (!sp_offboard.armed && current_status.flag_system_armed) {
- update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
- }
-
- } else {
- static uint64_t last_print_time = 0;
-
- /* print error message for first RC glitch and then every 5 s / 5000 ms) */
- if (!current_status.offboard_control_signal_weak || ((hrt_absolute_time() - last_print_time) > 5000000)) {
- current_status.offboard_control_signal_weak = true;
- mavlink_log_critical(mavlink_fd, "CRIT:NO OFFBOARD CONTROL!");
- last_print_time = hrt_absolute_time();
- }
-
- /* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
- current_status.offboard_control_signal_lost_interval = hrt_absolute_time() - sp_offboard.timestamp;
-
- /* if the signal is gone for 0.1 seconds, consider it lost */
- if (current_status.offboard_control_signal_lost_interval > 100000) {
- current_status.offboard_control_signal_lost = true;
- current_status.failsave_lowlevel_start_time = hrt_absolute_time();
- tune_confirm();
-
- /* kill motors after timeout */
- if (hrt_absolute_time() - current_status.failsave_lowlevel_start_time > failsafe_lowlevel_timeout_ms * 1000) {
- current_status.failsave_lowlevel = true;
- state_changed = true;
- }
- }
- }
- }
-
-
- current_status.counter++;
- current_status.timestamp = hrt_absolute_time();
-
-
- /* If full run came back clean, transition to standby */
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT &&
- current_status.flag_preflight_gyro_calibration == false &&
- current_status.flag_preflight_mag_calibration == false &&
- current_status.flag_preflight_accel_calibration == false) {
- /* All ok, no calibration going on, go to standby */
- do_state_update(stat_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- }
-
- /* publish at least with 1 Hz */
- if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 || state_changed) {
- publish_armed_status(&current_status);
- orb_publish(ORB_ID(vehicle_status), stat_pub, &current_status);
- state_changed = false;
- }
-
- /* Store old modes to detect and act on state transitions */
- voltage_previous = current_status.voltage_battery;
-
- fflush(stdout);
- counter++;
- usleep(COMMANDER_MONITORING_INTERVAL);
- }
-
- /* wait for threads to complete */
- // pthread_join(command_handling_thread, NULL);
- pthread_join(subsystem_info_thread, NULL);
-
- /* close fds */
- led_deinit();
- buzzer_deinit();
- close(sp_man_sub);
- close(sp_offboard_sub);
- close(global_position_sub);
- close(sensor_sub);
- close(cmd_sub);
-
- warnx("exiting..\n");
- fflush(stdout);
-
- thread_running = false;
-
- return 0;
-}
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
new file mode 100644
index 000000000..54219a34a
--- /dev/null
+++ b/src/modules/commander/commander.cpp
@@ -0,0 +1,1918 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
+ * Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 commander.cpp
+ * Main system state machine implementation.
+ *
+ */
+
+#include <nuttx/config.h>
+#include <pthread.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <systemlib/err.h>
+#include <debug.h>
+#include <sys/prctl.h>
+#include <sys/stat.h>
+#include <string.h>
+#include <math.h>
+#include <poll.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/offboard_control_setpoint.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/subsystem_info.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/safety.h>
+
+#include <drivers/drv_led.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <systemlib/cpuload.h>
+#include <systemlib/rc_check.h>
+
+#include "px4_custom_mode.h"
+#include "commander_helper.h"
+#include "state_machine_helper.h"
+#include "calibration_routines.h"
+#include "accelerometer_calibration.h"
+#include "gyro_calibration.h"
+#include "mag_calibration.h"
+#include "baro_calibration.h"
+#include "rc_calibration.h"
+#include "airspeed_calibration.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+extern struct system_load_s system_load;
+
+/* Decouple update interval and hysteris counters, all depends on intervals */
+#define COMMANDER_MONITORING_INTERVAL 50000
+#define COMMANDER_MONITORING_LOOPSPERMSEC (1/(COMMANDER_MONITORING_INTERVAL/1000.0f))
+
+#define MAVLINK_OPEN_INTERVAL 50000
+
+#define STICK_ON_OFF_LIMIT 0.75f
+#define STICK_THRUST_RANGE 1.0f
+#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
+#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
+
+#define POSITION_TIMEOUT 1000000 /**< consider the local or global position estimate invalid after 1s */
+#define RC_TIMEOUT 100000
+#define DIFFPRESS_TIMEOUT 2000000
+
+#define PRINT_INTERVAL 5000000
+#define PRINT_MODE_REJECT_INTERVAL 2000000
+
+enum MAV_MODE_FLAG {
+ MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1, /* 0b00000001 Reserved for future use. | */
+ MAV_MODE_FLAG_TEST_ENABLED = 2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
+ MAV_MODE_FLAG_AUTO_ENABLED = 4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
+ MAV_MODE_FLAG_GUIDED_ENABLED = 8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
+ MAV_MODE_FLAG_STABILIZE_ENABLED = 16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
+ MAV_MODE_FLAG_HIL_ENABLED = 32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
+ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64, /* 0b01000000 remote control input is enabled. | */
+ MAV_MODE_FLAG_SAFETY_ARMED = 128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
+ MAV_MODE_FLAG_ENUM_END = 129, /* | */
+};
+
+/* Mavlink file descriptors */
+static int mavlink_fd;
+
+/* flags */
+static bool commander_initialized = false;
+static volatile bool thread_should_exit = false; /**< daemon exit flag */
+static volatile bool thread_running = false; /**< daemon status flag */
+static int daemon_task; /**< Handle of daemon task / thread */
+
+static unsigned int leds_counter;
+/* To remember when last notification was sent */
+static uint64_t last_print_mode_reject_time = 0;
+/* if connected via USB */
+static bool on_usb_power = false;
+
+static float takeoff_alt = 5.0f;
+
+static struct vehicle_status_s status;
+
+/* armed topic */
+static struct actuator_armed_s armed;
+
+static struct safety_s safety;
+
+/* flags for control apps */
+struct vehicle_control_mode_s control_mode;
+
+/* tasks waiting for low prio thread */
+typedef enum {
+ LOW_PRIO_TASK_NONE = 0,
+ LOW_PRIO_TASK_PARAM_SAVE,
+ LOW_PRIO_TASK_PARAM_LOAD,
+ LOW_PRIO_TASK_GYRO_CALIBRATION,
+ LOW_PRIO_TASK_MAG_CALIBRATION,
+ LOW_PRIO_TASK_ALTITUDE_CALIBRATION,
+ LOW_PRIO_TASK_RC_CALIBRATION,
+ LOW_PRIO_TASK_ACCEL_CALIBRATION,
+ LOW_PRIO_TASK_AIRSPEED_CALIBRATION
+} low_prio_task_t;
+
+static low_prio_task_t low_prio_task = LOW_PRIO_TASK_NONE;
+
+/**
+ * The daemon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int commander_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+void usage(const char *reason);
+
+/**
+ * React to commands that are sent e.g. from the mavlink module.
+ */
+void handle_command(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed);
+
+/**
+ * Mainloop of commander.
+ */
+int commander_thread_main(int argc, char *argv[]);
+
+void control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed);
+
+void check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed);
+
+void check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *current_status);
+
+transition_result_t check_main_state_machine(struct vehicle_status_s *current_status);
+
+void print_reject_mode(struct vehicle_status_s *current_status, const char *msg);
+
+void print_reject_arm(const char *msg);
+
+void print_status();
+
+int arm();
+int disarm();
+
+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);
+
+/**
+ * Loop that runs at a lower rate and priority for calibration and parameter tasks.
+ */
+void *commander_low_prio_loop(void *arg);
+
+void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result);
+
+
+int commander_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("commander already running");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ daemon_task = task_spawn_cmd("commander",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 40,
+ 3000,
+ commander_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+
+ while (!thread_running) {
+ usleep(200);
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+
+ if (!thread_running)
+ errx(0, "commander already stopped");
+
+ thread_should_exit = true;
+
+ while (thread_running) {
+ usleep(200000);
+ warnx(".");
+ }
+
+ warnx("terminated.");
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("\tcommander is running");
+ print_status();
+
+ } else {
+ warnx("\tcommander not started");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "arm")) {
+ arm();
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "disarm")) {
+ disarm();
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+void usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
+ exit(1);
+}
+
+void print_status()
+{
+ warnx("usb powered: %s", (on_usb_power) ? "yes" : "no");
+
+ /* read all relevant states */
+ int state_sub = orb_subscribe(ORB_ID(vehicle_status));
+ struct vehicle_status_s state;
+ orb_copy(ORB_ID(vehicle_status), state_sub, &state);
+
+ const char *armed_str;
+
+ switch (state.arming_state) {
+ case ARMING_STATE_INIT:
+ armed_str = "INIT";
+ break;
+
+ case ARMING_STATE_STANDBY:
+ armed_str = "STANDBY";
+ break;
+
+ case ARMING_STATE_ARMED:
+ armed_str = "ARMED";
+ break;
+
+ case ARMING_STATE_ARMED_ERROR:
+ armed_str = "ARMED_ERROR";
+ break;
+
+ case ARMING_STATE_STANDBY_ERROR:
+ armed_str = "STANDBY_ERROR";
+ break;
+
+ case ARMING_STATE_REBOOT:
+ armed_str = "REBOOT";
+ break;
+
+ case ARMING_STATE_IN_AIR_RESTORE:
+ armed_str = "IN_AIR_RESTORE";
+ break;
+
+ default:
+ armed_str = "ERR: UNKNOWN STATE";
+ break;
+ }
+
+ close(state_sub);
+
+
+ warnx("arming: %s", armed_str);
+}
+
+static orb_advert_t control_mode_pub;
+static orb_advert_t status_pub;
+
+int arm()
+{
+ int arming_res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED, &armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
+ return 0;
+ } else {
+ return 1;
+ }
+}
+
+int disarm()
+{
+ int arming_res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
+ return 0;
+ } else {
+ return 1;
+ }
+}
+
+void handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed)
+{
+ /* result of the command */
+ uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+
+ /* only handle high-priority commands here */
+
+ /* request to set different system mode */
+ switch (cmd->command) {
+ case VEHICLE_CMD_DO_SET_MODE: {
+ uint8_t base_mode = (uint8_t) cmd->param1;
+ uint8_t custom_main_mode = (uint8_t) cmd->param2;
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ /* set HIL state */
+ hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF;
+ int hil_ret = hil_state_transition(new_hil_state, status_pub, status, control_mode_pub, control_mode, mavlink_fd);
+
+ /* if HIL got enabled, reset battery status state */
+ if (hil_ret == OK && control_mode->flag_system_hil_enabled) {
+ /* reset the arming mode to disarmed */
+ arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_STANDBY, armed);
+
+ if (arming_res != TRANSITION_DENIED) {
+ mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
+
+ } else {
+ mavlink_log_info(mavlink_fd, "[cmd] HIL: FAILED resetting armed state");
+ }
+ }
+
+ // TODO remove debug code
+ //mavlink_log_critical(mavlink_fd, "#audio: command setmode: %d %d", base_mode, custom_main_mode);
+ /* set arming state */
+ arming_res = TRANSITION_NOT_CHANGED;
+
+ if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
+ if ((safety->safety_switch_available && !safety->safety_off) && !control_mode->flag_system_hil_enabled) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+ arming_res = TRANSITION_DENIED;
+
+ } else {
+ arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
+ }
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by command");
+ }
+
+ } else {
+ if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ arming_state_t new_arming_state = (status->arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+ arming_res = arming_state_transition(status, safety, control_mode, new_arming_state, armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] DISARMED by command");
+ }
+
+ } else {
+ arming_res = TRANSITION_NOT_CHANGED;
+ }
+ }
+
+ /* set main state */
+ transition_result_t main_res = TRANSITION_DENIED;
+
+ if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
+ /* use autopilot-specific mode */
+ if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
+ /* SEATBELT */
+ main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
+ /* EASY */
+ main_res = main_state_transition(status, MAIN_STATE_EASY);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ }
+
+ } else {
+ /* use base mode */
+ if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
+ if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
+ /* EASY */
+ main_res = main_state_transition(status, MAIN_STATE_EASY);
+
+ } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
+ }
+ }
+
+ if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ break;
+ }
+
+ case VEHICLE_CMD_NAV_TAKEOFF: {
+ if (armed->armed) {
+ transition_result_t nav_res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
+
+ if (nav_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] TAKEOFF on command");
+ }
+
+ if (nav_res != TRANSITION_DENIED) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ } else {
+ /* reject TAKEOFF not armed */
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ break;
+ }
+
+ case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
+ if (safety->safety_switch_available && !safety->safety_off) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+ arming_res = TRANSITION_DENIED;
+
+ } else {
+ arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
+ }
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_critical(mavlink_fd, "#audio: ARMED by component arm cmd");
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ /* supported command handling stop */
+ if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
+ tune_positive();
+
+ } else if (result == VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ /* we do not care in the high prio loop about commands we don't know */
+ } else {
+ tune_negative();
+
+ if (result == VEHICLE_CMD_RESULT_DENIED) {
+ mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd->command);
+
+ } else if (result == VEHICLE_CMD_RESULT_FAILED) {
+ mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd->command);
+
+ } else if (result == VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED) {
+ mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command);
+
+ }
+ }
+
+ /* send any requested ACKs */
+ if (cmd->confirmation > 0 && result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ /* send acknowledge command */
+ // XXX TODO
+ }
+
+}
+
+int commander_thread_main(int argc, char *argv[])
+{
+ /* not yet initialized */
+ commander_initialized = false;
+ bool home_position_set = false;
+
+ bool battery_tune_played = false;
+ bool arm_tune_played = false;
+
+ /* set parameters */
+ param_t _param_sys_type = param_find("MAV_TYPE");
+ param_t _param_system_id = param_find("MAV_SYS_ID");
+ param_t _param_component_id = param_find("MAV_COMP_ID");
+ param_t _param_takeoff_alt = param_find("NAV_TAKEOFF_ALT");
+
+ /* welcome user */
+ warnx("starting");
+
+ /* pthread for slow low prio thread */
+ pthread_t commander_low_prio_thread;
+
+ /* initialize */
+ if (led_init() != 0) {
+ warnx("ERROR: Failed to initialize leds");
+ }
+
+ if (buzzer_init() != OK) {
+ warnx("ERROR: Failed to initialize buzzer");
+ }
+
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ /* Main state machine */
+ /* make sure we are in preflight state */
+ memset(&status, 0, sizeof(status));
+ status.condition_landed = true; // initialize to safe value
+ // We want to accept RC inputs as default
+ status.rc_input_blocked = false;
+
+ /* armed topic */
+ orb_advert_t armed_pub;
+ /* Initialize armed with all false */
+ memset(&armed, 0, sizeof(armed));
+
+ /* Initialize all flags to false */
+ memset(&control_mode, 0, sizeof(control_mode));
+
+ status.main_state = MAIN_STATE_MANUAL;
+ status.navigation_state = NAVIGATION_STATE_DIRECT;
+ status.arming_state = ARMING_STATE_INIT;
+ status.hil_state = HIL_STATE_OFF;
+
+ /* neither manual nor offboard control commands have been received */
+ status.offboard_control_signal_found_once = false;
+ status.rc_signal_found_once = false;
+
+ /* mark all signals lost as long as they haven't been found */
+ status.rc_signal_lost = true;
+ status.offboard_control_signal_lost = true;
+
+ /* allow manual override initially */
+ control_mode.flag_external_manual_override_ok = true;
+
+ /* set battery warning flag */
+ status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
+ status.condition_battery_voltage_valid = false;
+
+ // XXX for now just set sensors as initialized
+ status.condition_system_sensors_initialized = true;
+
+ // XXX just disable offboard control for now
+ control_mode.flag_control_offboard_enabled = false;
+
+ /* advertise to ORB */
+ status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
+ /* publish current state machine */
+
+ /* publish initial state */
+ status.counter++;
+ status.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+
+ armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
+
+ control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &control_mode);
+
+ /* home position */
+ orb_advert_t home_pub = -1;
+ struct home_position_s home;
+ memset(&home, 0, sizeof(home));
+
+ if (status_pub < 0) {
+ warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
+ warnx("exiting.");
+ exit(ERROR);
+ }
+
+ mavlink_log_info(mavlink_fd, "[cmd] started");
+
+ int ret;
+
+ pthread_attr_t commander_low_prio_attr;
+ pthread_attr_init(&commander_low_prio_attr);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2992);
+
+ struct sched_param param;
+ (void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
+
+ /* low priority */
+ param.sched_priority = SCHED_PRIORITY_DEFAULT - 50;
+ (void)pthread_attr_setschedparam(&commander_low_prio_attr, &param);
+ pthread_create(&commander_low_prio_thread, &commander_low_prio_attr, commander_low_prio_loop, NULL);
+ pthread_attr_destroy(&commander_low_prio_attr);
+
+ /* Start monitoring loop */
+ unsigned counter = 0;
+ unsigned stick_off_counter = 0;
+ unsigned stick_on_counter = 0;
+
+ bool low_battery_voltage_actions_done = false;
+ bool critical_battery_voltage_actions_done = false;
+
+ uint64_t last_idle_time = 0;
+ uint64_t start_time = 0;
+
+ bool status_changed = true;
+ bool param_init_forced = true;
+
+ bool updated = false;
+
+ bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+
+ /* Subscribe to safety topic */
+ int safety_sub = orb_subscribe(ORB_ID(safety));
+ memset(&safety, 0, sizeof(safety));
+ safety.safety_switch_available = false;
+ safety.safety_off = false;
+
+ /* Subscribe to manual control data */
+ int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ struct manual_control_setpoint_s sp_man;
+ memset(&sp_man, 0, sizeof(sp_man));
+
+ /* Subscribe to offboard control data */
+ int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
+ struct offboard_control_setpoint_s sp_offboard;
+ memset(&sp_offboard, 0, sizeof(sp_offboard));
+
+ /* Subscribe to global position */
+ int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ struct vehicle_global_position_s global_position;
+ memset(&global_position, 0, sizeof(global_position));
+
+ /* Subscribe to local position data */
+ int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
+ struct vehicle_local_position_s local_position;
+ memset(&local_position, 0, sizeof(local_position));
+
+ /*
+ * The home position is set based on GPS only, to prevent a dependency between
+ * position estimator and commander. RAW GPS is more than good enough for a
+ * non-flying vehicle.
+ */
+
+ /* Subscribe to GPS topic */
+ int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ struct vehicle_gps_position_s gps_position;
+ memset(&gps_position, 0, sizeof(gps_position));
+
+ /* Subscribe to sensor topic */
+ int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ struct sensor_combined_s sensors;
+ memset(&sensors, 0, sizeof(sensors));
+
+ /* Subscribe to differential pressure topic */
+ int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
+ struct differential_pressure_s diff_pres;
+ memset(&diff_pres, 0, sizeof(diff_pres));
+
+ /* Subscribe to command topic */
+ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ struct vehicle_command_s cmd;
+ memset(&cmd, 0, sizeof(cmd));
+
+ /* Subscribe to parameters changed topic */
+ int param_changed_sub = orb_subscribe(ORB_ID(parameter_update));
+ struct parameter_update_s param_changed;
+ memset(&param_changed, 0, sizeof(param_changed));
+
+ /* Subscribe to battery topic */
+ int battery_sub = orb_subscribe(ORB_ID(battery_status));
+ struct battery_status_s battery;
+ memset(&battery, 0, sizeof(battery));
+
+ /* Subscribe to subsystem info topic */
+ int subsys_sub = orb_subscribe(ORB_ID(subsystem_info));
+ struct subsystem_info_s info;
+ memset(&info, 0, sizeof(info));
+
+ control_status_leds(&status, &armed, true);
+
+ /* now initialized */
+ commander_initialized = true;
+ thread_running = true;
+
+ start_time = hrt_absolute_time();
+
+ while (!thread_should_exit) {
+
+ if (mavlink_fd < 0 && counter % (1000000 / MAVLINK_OPEN_INTERVAL) == 0) {
+ /* try to open the mavlink log device every once in a while */
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ }
+
+ /* update parameters */
+ orb_check(param_changed_sub, &updated);
+
+ if (updated || param_init_forced) {
+ param_init_forced = false;
+ /* parameters changed */
+ orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
+
+ /* update parameters */
+ if (!armed.armed) {
+ if (param_get(_param_sys_type, &(status.system_type)) != OK) {
+ warnx("failed getting new system type");
+ }
+
+ /* disable manual override for all systems that rely on electronic stabilization */
+ if (status.system_type == VEHICLE_TYPE_COAXIAL ||
+ status.system_type == VEHICLE_TYPE_HELICOPTER ||
+ status.system_type == VEHICLE_TYPE_TRICOPTER ||
+ status.system_type == VEHICLE_TYPE_QUADROTOR ||
+ status.system_type == VEHICLE_TYPE_HEXAROTOR ||
+ status.system_type == VEHICLE_TYPE_OCTOROTOR) {
+ control_mode.flag_external_manual_override_ok = false;
+ status.is_rotary_wing = true;
+
+ } else {
+ control_mode.flag_external_manual_override_ok = true;
+ status.is_rotary_wing = false;
+ }
+
+ /* check and update system / component ID */
+ param_get(_param_system_id, &(status.system_id));
+ param_get(_param_component_id, &(status.component_id));
+ status_changed = true;
+
+ /* re-check RC calibration */
+ rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+
+ /* navigation parameters */
+ param_get(_param_takeoff_alt, &takeoff_alt);
+ }
+ }
+
+ orb_check(sp_man_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(manual_control_setpoint), sp_man_sub, &sp_man);
+ }
+
+ orb_check(sp_offboard_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
+ }
+
+ orb_check(sensor_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
+ }
+
+ orb_check(diff_pres_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+ }
+
+ check_valid(diff_pres.timestamp, DIFFPRESS_TIMEOUT, true, &(status.condition_airspeed_valid), &status_changed);
+
+ /* update safety topic */
+ orb_check(safety_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(safety), safety_sub, &safety);
+
+ // XXX this would be the right approach to do it, but do we *WANT* this?
+ // /* disarm if safety is now on and still armed */
+ // if (safety.safety_switch_available && !safety.safety_off) {
+ // (void)arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ // }
+ }
+
+ /* update global position estimate */
+ orb_check(global_position_sub, &updated);
+
+ if (updated) {
+ /* position changed */
+ orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_position);
+ }
+
+ /* update condition_global_position_valid */
+ check_valid(global_position.timestamp, POSITION_TIMEOUT, global_position.valid, &(status.condition_global_position_valid), &status_changed);
+
+ /* update local position estimate */
+ orb_check(local_position_sub, &updated);
+
+ if (updated) {
+ /* position changed */
+ orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
+ }
+
+ /* update condition_local_position_valid and condition_local_altitude_valid */
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid, &(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.is_rotary_wing && status.condition_local_altitude_valid) {
+ if (status.condition_landed != local_position.landed) {
+ status.condition_landed = local_position.landed;
+ status_changed = true;
+
+ if (status.condition_landed) {
+ mavlink_log_critical(mavlink_fd, "#audio: LANDED");
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: IN AIR");
+ }
+ }
+ }
+
+ /* update battery status */
+ orb_check(battery_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(battery_status), battery_sub, &battery);
+ /* only consider battery voltage if system has been running 2s and battery voltage is valid */
+ if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
+ status.battery_voltage = battery.voltage_filtered_v;
+ status.battery_current = battery.current_a;
+ status.condition_battery_voltage_valid = true;
+ status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah);
+ }
+ }
+
+ /* update subsystem */
+ orb_check(subsys_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(subsystem_info), subsys_sub, &info);
+
+ warnx("subsystem changed: %d\n", (int)info.subsystem_type);
+
+ /* mark / unmark as present */
+ if (info.present) {
+ status.onboard_control_sensors_present |= info.subsystem_type;
+
+ } else {
+ status.onboard_control_sensors_present &= ~info.subsystem_type;
+ }
+
+ /* mark / unmark as enabled */
+ if (info.enabled) {
+ status.onboard_control_sensors_enabled |= info.subsystem_type;
+
+ } else {
+ status.onboard_control_sensors_enabled &= ~info.subsystem_type;
+ }
+
+ /* mark / unmark as ok */
+ if (info.ok) {
+ status.onboard_control_sensors_health |= info.subsystem_type;
+
+ } else {
+ status.onboard_control_sensors_health &= ~info.subsystem_type;
+ }
+
+ status_changed = true;
+ }
+
+ if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
+ /* compute system load */
+ uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
+
+ if (last_idle_time > 0)
+ status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+
+ 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);
+ }
+
+ /* if battery voltage is getting lower, warn using buzzer, etc. */
+ if (status.condition_battery_voltage_valid && status.battery_remaining < 0.25f && !low_battery_voltage_actions_done) {
+ low_battery_voltage_actions_done = true;
+ mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY");
+ status.battery_warning = VEHICLE_BATTERY_WARNING_LOW;
+ status_changed = true;
+ battery_tune_played = false;
+
+ } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !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_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY");
+ status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
+ battery_tune_played = false;
+
+ if (armed.armed) {
+ arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED_ERROR, &armed);
+
+ } else {
+ arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY_ERROR, &armed);
+ }
+
+ status_changed = true;
+ }
+
+ /* End battery voltage check */
+
+ /* If in INIT state, try to proceed to STANDBY state */
+ if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
+ // XXX check for sensors
+ arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+
+ } else {
+ // XXX: Add emergency stuff if sensors are lost
+ }
+
+
+ /*
+ * Check for valid position information.
+ *
+ * If the system has a valid position source from an onboard
+ * position estimator, it is safe to operate it autonomously.
+ * The flag_vector_flight_mode_ok flag indicates that a minimum
+ * set of position measurements is available.
+ */
+
+ orb_check(gps_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
+ /* check if GPS fix is ok */
+ float hdop_threshold_m = 4.0f;
+ float vdop_threshold_m = 8.0f;
+
+ /*
+ * If horizontal dilution of precision (hdop / eph)
+ * and vertical diluation of precision (vdop / epv)
+ * are below a certain threshold (e.g. 4 m), AND
+ * home position is not yet set AND the last GPS
+ * GPS measurement is not older than two seconds AND
+ * the system is currently not armed, set home
+ * position to the current position.
+ */
+
+ if (!home_position_set && gps_position.fix_type >= 3 &&
+ (gps_position.eph_m < hdop_threshold_m) && (gps_position.epv_m < vdop_threshold_m) && // XXX note that vdop is 0 for mtk
+ (hrt_absolute_time() < gps_position.timestamp_position + POSITION_TIMEOUT) && !armed.armed) {
+ /* copy position data to uORB home message, store it locally as well */
+ // TODO use global position estimate
+ home.lat = gps_position.lat;
+ home.lon = gps_position.lon;
+ home.alt = gps_position.alt;
+
+ home.eph_m = gps_position.eph_m;
+ home.epv_m = gps_position.epv_m;
+
+ home.s_variance_m_s = gps_position.s_variance_m_s;
+ home.p_variance_m = gps_position.p_variance_m;
+
+ double home_lat_d = home.lat * 1e-7;
+ double home_lon_d = home.lon * 1e-7;
+ warnx("home: lat = %.7f, lon = %.7f", home_lat_d, home_lon_d);
+ mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f", home_lat_d, home_lon_d);
+
+ /* announce new home position */
+ if (home_pub > 0) {
+ orb_publish(ORB_ID(home_position), home_pub, &home);
+
+ } else {
+ home_pub = orb_advertise(ORB_ID(home_position), &home);
+ }
+
+ /* mark home position as set */
+ home_position_set = true;
+ tune_positive();
+ }
+ }
+
+ /* ignore RC signals if in offboard control mode */
+ if (!status.offboard_control_signal_found_once && sp_man.timestamp != 0 && !status.rc_input_blocked) {
+ /* start RC input check */
+ if (hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
+ /* handle the case where RC signal was regained */
+ if (!status.rc_signal_found_once) {
+ status.rc_signal_found_once = true;
+ mavlink_log_critical(mavlink_fd, "#audio: detected RC signal first time");
+ status_changed = true;
+
+ } else {
+ if (status.rc_signal_lost) {
+ mavlink_log_critical(mavlink_fd, "#audio: RC signal regained");
+ status_changed = true;
+ }
+ }
+
+ status.rc_signal_lost = false;
+
+ transition_result_t res; // store all transitions results here
+
+ /* arm/disarm by RC */
+ res = TRANSITION_NOT_CHANGED;
+
+ /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm
+ * do it only for rotary wings */
+ if (status.is_rotary_wing &&
+ (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
+ (status.main_state == MAIN_STATE_MANUAL || status.navigation_state == NAVIGATION_STATE_AUTO_READY ||
+ (status.condition_landed && (
+ status.navigation_state == NAVIGATION_STATE_ALTHOLD ||
+ status.navigation_state == NAVIGATION_STATE_VECTOR
+ ))) && sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
+ 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);
+ res = arming_state_transition(&status, &safety, &control_mode, new_arming_state, &armed);
+ stick_off_counter = 0;
+
+ } else {
+ stick_off_counter++;
+ }
+
+ } else {
+ stick_off_counter = 0;
+ }
+
+ /* check if left stick is in lower right position and we're in MANUAL mode -> arm */
+ if (status.arming_state == ARMING_STATE_STANDBY &&
+ sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
+ if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
+ if (safety.safety_switch_available && !safety.safety_off) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+
+ } else if (status.main_state != MAIN_STATE_MANUAL) {
+ print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
+
+ } else {
+ res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED, &armed);
+ }
+
+ stick_on_counter = 0;
+
+ } else {
+ stick_on_counter++;
+ }
+
+ } else {
+ stick_on_counter = 0;
+ }
+
+ if (res == TRANSITION_CHANGED) {
+ if (status.arming_state == ARMING_STATE_ARMED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
+
+ } else {
+ mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
+ }
+
+ } else if (res == TRANSITION_DENIED) {
+ warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ }
+
+ /* fill current_status according to mode switches */
+ check_mode_switches(&sp_man, &status);
+
+ /* evaluate the main state machine */
+ res = check_main_state_machine(&status);
+
+ if (res == TRANSITION_CHANGED) {
+ //mavlink_log_info(mavlink_fd, "[cmd] main state: %d", status.main_state);
+ tune_positive();
+
+ } else if (res == TRANSITION_DENIED) {
+ /* DENIED here indicates bug in the commander */
+ warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ }
+
+ } else {
+ if (!status.rc_signal_lost) {
+ mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST");
+ status.rc_signal_lost = true;
+ status_changed = true;
+ }
+ }
+ }
+
+
+ /* handle commands last, as the system needs to be updated to handle them */
+ orb_check(cmd_sub, &updated);
+
+ if (updated) {
+ /* got command */
+ orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
+
+ /* handle it */
+ handle_command(&status, &safety, &control_mode, &cmd, &armed);
+ }
+
+ /* evaluate the navigation state machine */
+ transition_result_t res = check_navigation_state_machine(&status, &control_mode, &local_position);
+
+ if (res == TRANSITION_DENIED) {
+ /* DENIED here indicates bug in the commander */
+ warnx("ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
+ mavlink_log_critical(mavlink_fd, "#audio: ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
+ }
+
+ /* check which state machines for changes, clear "changed" flag */
+ bool arming_state_changed = check_arming_state_changed();
+ bool main_state_changed = check_main_state_changed();
+ bool navigation_state_changed = check_navigation_state_changed();
+
+ hrt_abstime t1 = hrt_absolute_time();
+
+ if (navigation_state_changed || arming_state_changed) {
+ control_mode.flag_armed = armed.armed; // copy armed state to vehicle_control_mode topic
+ }
+
+ if (arming_state_changed || main_state_changed || navigation_state_changed) {
+ mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d, nav %d", status.arming_state, status.main_state, status.navigation_state);
+ status_changed = true;
+ }
+
+ /* publish states (armed, control mode, vehicle status) at least with 5 Hz */
+ if (counter % (200000 / COMMANDER_MONITORING_INTERVAL) == 0 || status_changed) {
+ status.timestamp = t1;
+ orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+ control_mode.timestamp = t1;
+ orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
+ armed.timestamp = t1;
+ orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
+ }
+
+ /* play arming and battery warning tunes */
+ if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) {
+ /* play tune when armed */
+ if (tune_arm() == OK)
+ arm_tune_played = true;
+
+ } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
+ /* play tune on battery warning */
+ if (tune_low_bat() == OK)
+ battery_tune_played = true;
+
+ } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
+ /* play tune on battery critical */
+ if (tune_critical_bat() == OK)
+ battery_tune_played = true;
+
+ } else if (battery_tune_played) {
+ tune_stop();
+ battery_tune_played = false;
+ }
+
+ /* reset arm_tune_played when disarmed */
+ if (status.arming_state != ARMING_STATE_ARMED || (safety.safety_switch_available && !safety.safety_off)) {
+ arm_tune_played = false;
+ }
+
+ fflush(stdout);
+ counter++;
+
+ int blink_state = blink_msg_state();
+
+ if (blink_state > 0) {
+ /* blinking LED message, don't touch LEDs */
+ if (blink_state == 2) {
+ /* blinking LED message completed, restore normal state */
+ control_status_leds(&status, &armed, true);
+ }
+
+ } else {
+ /* normal state */
+ control_status_leds(&status, &armed, status_changed);
+ }
+
+ status_changed = false;
+
+ usleep(COMMANDER_MONITORING_INTERVAL);
+ }
+
+ /* wait for threads to complete */
+ ret = pthread_join(commander_low_prio_thread, NULL);
+
+ if (ret) {
+ warn("join failed: %d", ret);
+ }
+
+ rgbled_set_mode(RGBLED_MODE_OFF);
+
+ /* close fds */
+ led_deinit();
+ buzzer_deinit();
+ close(sp_man_sub);
+ close(sp_offboard_sub);
+ close(local_position_sub);
+ close(global_position_sub);
+ close(gps_sub);
+ close(sensor_sub);
+ close(safety_sub);
+ close(cmd_sub);
+ close(subsys_sub);
+ close(diff_pres_sub);
+ close(param_changed_sub);
+ close(battery_sub);
+
+ thread_running = false;
+
+ return 0;
+}
+
+void
+check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed)
+{
+ hrt_abstime t = hrt_absolute_time();
+ bool valid_new = (t < timestamp + timeout && t > timeout && valid_in);
+
+ if (*valid_out != valid_new) {
+ *valid_out = valid_new;
+ *changed = true;
+ }
+}
+
+void
+control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed)
+{
+ /* driving rgbled */
+ if (changed) {
+ bool set_normal_color = false;
+
+ /* set mode */
+ if (status->arming_state == ARMING_STATE_ARMED) {
+ rgbled_set_mode(RGBLED_MODE_ON);
+ set_normal_color = true;
+
+ } else if (status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+ rgbled_set_color(RGBLED_COLOR_RED);
+
+ } else if (status->arming_state == ARMING_STATE_STANDBY) {
+ rgbled_set_mode(RGBLED_MODE_BREATHE);
+ set_normal_color = true;
+
+ } else { // STANDBY_ERROR and other states
+ rgbled_set_mode(RGBLED_MODE_BLINK_NORMAL);
+ rgbled_set_color(RGBLED_COLOR_RED);
+ }
+
+ if (set_normal_color) {
+ /* set color */
+ if (status->battery_warning != VEHICLE_BATTERY_WARNING_NONE) {
+ if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
+ rgbled_set_color(RGBLED_COLOR_AMBER);
+ }
+
+ /* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */
+
+ } else {
+ if (status->condition_local_position_valid) {
+ rgbled_set_color(RGBLED_COLOR_GREEN);
+
+ } else {
+ rgbled_set_color(RGBLED_COLOR_BLUE);
+ }
+ }
+ }
+ }
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
+ if (actuator_armed->armed) {
+ /* armed, solid */
+ led_on(LED_BLUE);
+
+ } else if (actuator_armed->ready_to_arm) {
+ /* ready to arm, blink at 1Hz */
+ if (leds_counter % 20 == 0)
+ led_toggle(LED_BLUE);
+
+ } else {
+ /* not ready to arm, blink at 10Hz */
+ if (leds_counter % 2 == 0)
+ led_toggle(LED_BLUE);
+ }
+
+#endif
+
+ /* give system warnings on error LED, XXX maybe add memory usage warning too */
+ if (status->load > 0.95f) {
+ if (leds_counter % 2 == 0)
+ led_toggle(LED_AMBER);
+
+ } else {
+ led_off(LED_AMBER);
+ }
+
+ leds_counter++;
+}
+
+void
+check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *current_status)
+{
+ /* main mode switch */
+ if (!isfinite(sp_man->mode_switch)) {
+ /* default to manual if signal is invalid */
+ current_status->mode_switch = MODE_SWITCH_MANUAL;
+
+ } else if (sp_man->mode_switch > STICK_ON_OFF_LIMIT) {
+ current_status->mode_switch = MODE_SWITCH_AUTO;
+
+ } else if (sp_man->mode_switch < -STICK_ON_OFF_LIMIT) {
+ current_status->mode_switch = MODE_SWITCH_MANUAL;
+
+ } else {
+ current_status->mode_switch = MODE_SWITCH_ASSISTED;
+ }
+
+ /* land switch */
+ if (!isfinite(sp_man->return_switch)) {
+ current_status->return_switch = RETURN_SWITCH_NONE;
+
+ } else if (sp_man->return_switch > STICK_ON_OFF_LIMIT) {
+ current_status->return_switch = RETURN_SWITCH_RETURN;
+
+ } else {
+ current_status->return_switch = RETURN_SWITCH_NONE;
+ }
+
+ /* assisted switch */
+ if (!isfinite(sp_man->assisted_switch)) {
+ current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
+
+ } else if (sp_man->assisted_switch > STICK_ON_OFF_LIMIT) {
+ current_status->assisted_switch = ASSISTED_SWITCH_EASY;
+
+ } else {
+ current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
+ }
+
+ /* mission switch */
+ if (!isfinite(sp_man->mission_switch)) {
+ current_status->mission_switch = MISSION_SWITCH_MISSION;
+
+ } else if (sp_man->mission_switch > STICK_ON_OFF_LIMIT) {
+ current_status->mission_switch = MISSION_SWITCH_NONE;
+
+ } else {
+ current_status->mission_switch = MISSION_SWITCH_MISSION;
+ }
+}
+
+transition_result_t
+check_main_state_machine(struct vehicle_status_s *current_status)
+{
+ /* evaluate the main state machine */
+ transition_result_t res = TRANSITION_DENIED;
+
+ switch (current_status->mode_switch) {
+ case MODE_SWITCH_MANUAL:
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
+
+ case MODE_SWITCH_ASSISTED:
+ if (current_status->assisted_switch == ASSISTED_SWITCH_EASY) {
+ res = main_state_transition(current_status, MAIN_STATE_EASY);
+
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
+
+ // else fallback to SEATBELT
+ print_reject_mode(current_status, "EASY");
+ }
+
+ res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this mode
+
+ if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
+ print_reject_mode(current_status, "SEATBELT");
+
+ // else fallback to MANUAL
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
+
+ case MODE_SWITCH_AUTO:
+ res = main_state_transition(current_status, MAIN_STATE_AUTO);
+
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
+
+ // else fallback to SEATBELT (EASY likely will not work too)
+ print_reject_mode(current_status, "AUTO");
+ res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
+
+ // else fallback to MANUAL
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
+
+ default:
+ break;
+ }
+
+ return res;
+}
+
+void
+print_reject_mode(struct vehicle_status_s *current_status, const char *msg)
+{
+ hrt_abstime t = hrt_absolute_time();
+
+ if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
+ last_print_mode_reject_time = t;
+ char s[80];
+ sprintf(s, "#audio: REJECT %s", msg);
+ mavlink_log_critical(mavlink_fd, s);
+
+ // only buzz if armed, because else we're driving people nuts indoors
+ // they really need to look at the leds as well.
+ if (current_status->arming_state == ARMING_STATE_ARMED) {
+ tune_negative();
+ } else {
+
+ // Always show the led indication
+ led_negative();
+ }
+ }
+}
+
+void
+print_reject_arm(const char *msg)
+{
+ hrt_abstime t = hrt_absolute_time();
+
+ if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
+ last_print_mode_reject_time = t;
+ char s[80];
+ sprintf(s, "#audio: %s", msg);
+ mavlink_log_critical(mavlink_fd, s);
+ tune_negative();
+ }
+}
+
+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 res = TRANSITION_DENIED;
+
+ if (status->main_state == MAIN_STATE_AUTO) {
+ if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ // TODO AUTO_LAND handling
+ if (status->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+ /* don't switch to other states until takeoff not completed */
+ // XXX: only respect the condition_landed when the local position is actually valid
+ if (status->is_rotary_wing && status->condition_local_altitude_valid && (local_pos->z > -takeoff_alt || status->condition_landed)) {
+ return TRANSITION_NOT_CHANGED;
+ }
+ }
+
+ if (status->navigation_state != NAVIGATION_STATE_AUTO_TAKEOFF &&
+ status->navigation_state != NAVIGATION_STATE_AUTO_LOITER &&
+ status->navigation_state != NAVIGATION_STATE_AUTO_MISSION &&
+ status->navigation_state != NAVIGATION_STATE_AUTO_RTL) {
+ /* possibly on ground, switch to TAKEOFF if needed */
+ if (status->is_rotary_wing && status->condition_local_altitude_valid && (local_pos->z > -takeoff_alt || status->condition_landed)) {
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
+ return res;
+ }
+ }
+
+ /* switch to AUTO mode */
+ if (status->rc_signal_found_once && !status->rc_signal_lost) {
+ /* act depending on switches when manual control enabled */
+ if (status->return_switch == RETURN_SWITCH_RETURN) {
+ /* RTL */
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_RTL, control_mode);
+
+ } else {
+ if (status->mission_switch == MISSION_SWITCH_MISSION) {
+ /* MISSION */
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
+
+ } else {
+ /* LOITER */
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_LOITER, control_mode);
+ }
+ }
+
+ } else {
+ /* switch to MISSION when no RC control and first time in some AUTO mode */
+ if (status->navigation_state == NAVIGATION_STATE_AUTO_LOITER ||
+ status->navigation_state == NAVIGATION_STATE_AUTO_MISSION ||
+ status->navigation_state == NAVIGATION_STATE_AUTO_RTL ||
+ status->navigation_state == NAVIGATION_STATE_AUTO_LAND) {
+ res = TRANSITION_NOT_CHANGED;
+
+ } else {
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
+ }
+ }
+
+ } else {
+ /* disarmed, always switch to AUTO_READY */
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_READY, control_mode);
+ }
+
+ } else {
+ /* manual control modes */
+ if (status->rc_signal_lost && (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR)) {
+ /* switch to failsafe mode */
+ bool manual_control_old = control_mode->flag_control_manual_enabled;
+
+ if (!status->condition_landed && status->condition_local_position_valid) {
+ /* in air: try to hold position if possible */
+ res = navigation_state_transition(status, NAVIGATION_STATE_VECTOR, control_mode);
+
+ } else {
+ /* landed: don't try to hold position but land (if taking off) */
+ res = TRANSITION_DENIED;
+ }
+
+ if (res == TRANSITION_DENIED) {
+ res = navigation_state_transition(status, NAVIGATION_STATE_ALTHOLD, control_mode);
+ }
+
+ control_mode->flag_control_manual_enabled = false;
+
+ if (res == TRANSITION_NOT_CHANGED && manual_control_old) {
+ /* mark navigation state as changed to force immediate flag publishing */
+ set_navigation_state_changed();
+ res = TRANSITION_CHANGED;
+ }
+
+ if (res == TRANSITION_CHANGED) {
+ if (control_mode->flag_control_position_enabled) {
+ mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: POS HOLD");
+
+ } else {
+ if (status->condition_landed) {
+ mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: ALT HOLD (LAND)");
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: ALT HOLD");
+ }
+ }
+ }
+
+ } else {
+ switch (status->main_state) {
+ case MAIN_STATE_MANUAL:
+ res = navigation_state_transition(status, status->is_rotary_wing ? NAVIGATION_STATE_STABILIZE : NAVIGATION_STATE_DIRECT, control_mode);
+ break;
+
+ case MAIN_STATE_SEATBELT:
+ res = navigation_state_transition(status, NAVIGATION_STATE_ALTHOLD, control_mode);
+ break;
+
+ case MAIN_STATE_EASY:
+ res = navigation_state_transition(status, NAVIGATION_STATE_VECTOR, control_mode);
+ break;
+
+ default:
+ break;
+ }
+ }
+ }
+
+ return res;
+}
+
+void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result)
+{
+ switch (result) {
+ case VEHICLE_CMD_RESULT_ACCEPTED:
+ tune_positive();
+ break;
+
+ case VEHICLE_CMD_RESULT_DENIED:
+ mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd.command);
+ tune_negative();
+ break;
+
+ case VEHICLE_CMD_RESULT_FAILED:
+ mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd.command);
+ tune_negative();
+ break;
+
+ case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
+ mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd.command);
+ tune_negative();
+ break;
+
+ case VEHICLE_CMD_RESULT_UNSUPPORTED:
+ mavlink_log_critical(mavlink_fd, "#audio: command unsupported: %u", cmd.command);
+ tune_negative();
+ break;
+
+ default:
+ break;
+ }
+}
+
+void *commander_low_prio_loop(void *arg)
+{
+ /* Set thread name */
+ prctl(PR_SET_NAME, "commander_low_prio", getpid());
+
+ /* Subscribe to command topic */
+ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ struct vehicle_command_s cmd;
+ memset(&cmd, 0, sizeof(cmd));
+
+ /* wakeup source(s) */
+ struct pollfd fds[1];
+
+ /* use the gyro to pace output - XXX BROKEN if we are using the L3GD20 */
+ fds[0].fd = cmd_sub;
+ fds[0].events = POLLIN;
+
+ while (!thread_should_exit) {
+ /* wait for up to 200ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 200);
+
+ /* timed out - periodic check for thread_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* 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;
+ }
+
+ /* if we reach here, we have a valid command */
+ orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
+
+ /* ignore commands the high-prio loop handles */
+ if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
+ cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
+ cmd.command == VEHICLE_CMD_NAV_TAKEOFF)
+ continue;
+
+ /* only handle low-priority commands here */
+ switch (cmd.command) {
+
+ case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
+ if (is_safe(&status, &safety, &armed)) {
+
+ if (((int)(cmd.param1)) == 1) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ usleep(100000);
+ /* reboot */
+ systemreset(false);
+
+ } else if (((int)(cmd.param1)) == 3) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ usleep(100000);
+ /* reboot to bootloader */
+ systemreset(true);
+
+ } else {
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ }
+
+ } else {
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ }
+
+ break;
+
+ case VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
+
+ int calib_ret = ERROR;
+
+ /* try to go to INIT/PREFLIGHT arming state */
+
+ // XXX disable interrupts in arming_state_transition
+ if (TRANSITION_DENIED == arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_INIT, &armed)) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ break;
+ }
+
+ if ((int)(cmd.param1) == 1) {
+ /* gyro calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_gyro_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param2) == 1) {
+ /* magnetometer calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_mag_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param3) == 1) {
+ /* zero-altitude pressure calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+
+ } else if ((int)(cmd.param4) == 1) {
+ /* RC calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ /* disable RC control input completely */
+ status.rc_input_blocked = true;
+ calib_ret = OK;
+ mavlink_log_info(mavlink_fd, "CAL: Disabling RC IN");
+
+ } else if ((int)(cmd.param4) == 2) {
+ /* RC trim calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_trim_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param5) == 1) {
+ /* accelerometer calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_accel_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param6) == 1) {
+ /* airspeed calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_airspeed_calibration(mavlink_fd);
+ } else if ((int)(cmd.param4) == 0) {
+ /* RC calibration ended - have we been in one worth confirming? */
+ if (status.rc_input_blocked) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ /* enable RC control input */
+ status.rc_input_blocked = false;
+ mavlink_log_info(mavlink_fd, "CAL: Re-enabling RC IN");
+ }
+
+ /* this always succeeds */
+ calib_ret = OK;
+
+ }
+
+ if (calib_ret == OK)
+ tune_positive();
+ else
+ tune_negative();
+
+ arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+
+ break;
+ }
+
+ case VEHICLE_CMD_PREFLIGHT_STORAGE: {
+
+ if (((int)(cmd.param1)) == 0) {
+ int ret = param_load_default();
+
+ if (ret == OK) {
+ mavlink_log_info(mavlink_fd, "[cmd] parameters loaded");
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: parameters load ERROR");
+
+ /* convenience as many parts of NuttX use negative errno */
+ if (ret < 0)
+ ret = -ret;
+
+ if (ret < 1000)
+ mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+
+ answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
+ }
+
+ } else if (((int)(cmd.param1)) == 1) {
+ int ret = param_save_default();
+
+ if (ret == OK) {
+ mavlink_log_info(mavlink_fd, "[cmd] parameters saved");
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: parameters save error");
+
+ /* convenience as many parts of NuttX use negative errno */
+ if (ret < 0)
+ ret = -ret;
+
+ if (ret < 1000)
+ mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+
+ answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
+ }
+ }
+
+ break;
+ }
+
+ case VEHICLE_CMD_START_RX_PAIR:
+ /* handled in the IO driver */
+ break;
+
+ default:
+ answer_command(cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
+ break;
+ }
+
+ /* send any requested ACKs */
+ if (cmd.confirmation > 0 && cmd.command != VEHICLE_CMD_DO_SET_MODE
+ && cmd.command != VEHICLE_CMD_COMPONENT_ARM_DISARM) {
+ /* send acknowledge command */
+ // XXX TODO
+ }
+ }
+
+ close(cmd_sub);
+
+ return NULL;
+}
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
new file mode 100644
index 000000000..033e7dc88
--- /dev/null
+++ b/src/modules/commander/commander_helper.cpp
@@ -0,0 +1,306 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 commander_helper.cpp
+ * Commander helper functions implementations
+ */
+
+#include <stdio.h>
+#include <unistd.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <math.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+#include <drivers/drv_led.h>
+#include <drivers/drv_rgbled.h>
+
+#include "commander_helper.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#define BLINK_MSG_TIME 700000 // 3 fast blinks
+
+bool is_multirotor(const struct vehicle_status_s *current_status)
+{
+ return ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_OCTOROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_TRICOPTER));
+}
+
+bool is_rotary_wing(const struct vehicle_status_s *current_status)
+{
+ return is_multirotor(current_status) || (current_status->system_type == VEHICLE_TYPE_HELICOPTER)
+ || (current_status->system_type == VEHICLE_TYPE_COAXIAL);
+}
+
+static int buzzer;
+static hrt_abstime blink_msg_end;
+
+int buzzer_init()
+{
+ buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY);
+
+ if (buzzer < 0) {
+ warnx("Buzzer: open fail\n");
+ return ERROR;
+ }
+
+ return OK;
+}
+
+void buzzer_deinit()
+{
+ close(buzzer);
+}
+
+void tune_error()
+{
+ ioctl(buzzer, TONE_SET_ALARM, TONE_ERROR_TUNE);
+}
+
+void tune_positive()
+{
+ blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
+ rgbled_set_color(RGBLED_COLOR_GREEN);
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+ ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_POSITIVE_TUNE);
+}
+
+void tune_neutral()
+{
+ blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
+ rgbled_set_color(RGBLED_COLOR_WHITE);
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+ ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEUTRAL_TUNE);
+}
+
+void tune_negative()
+{
+ led_negative();
+ ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
+}
+
+void led_negative()
+{
+ blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
+ rgbled_set_color(RGBLED_COLOR_RED);
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+}
+
+int tune_arm()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, TONE_ARMING_WARNING_TUNE);
+}
+
+int tune_low_bat()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, TONE_BATTERY_WARNING_SLOW_TUNE);
+}
+
+int tune_critical_bat()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, TONE_BATTERY_WARNING_FAST_TUNE);
+}
+
+void tune_stop()
+{
+ ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE);
+}
+
+int blink_msg_state()
+{
+ if (blink_msg_end == 0) {
+ return 0;
+
+ } else if (hrt_absolute_time() > blink_msg_end) {
+ return 2;
+
+ } else {
+ return 1;
+ }
+}
+
+static int leds;
+static int rgbleds;
+
+int led_init()
+{
+ blink_msg_end = 0;
+
+ /* first open normal LEDs */
+ leds = open(LED_DEVICE_PATH, 0);
+
+ if (leds < 0) {
+ warnx("LED: open fail\n");
+ return ERROR;
+ }
+
+ /* the blue LED is only available on FMUv1 but not FMUv2 */
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ if (ioctl(leds, LED_ON, LED_BLUE)) {
+ warnx("Blue LED: ioctl fail\n");
+ return ERROR;
+ }
+
+#endif
+
+ if (ioctl(leds, LED_ON, LED_AMBER)) {
+ warnx("Amber LED: ioctl fail\n");
+ return ERROR;
+ }
+
+ /* then try RGB LEDs, this can fail on FMUv1*/
+ rgbleds = open(RGBLED_DEVICE_PATH, 0);
+
+ if (rgbleds == -1) {
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+#else
+ warnx("No RGB LED found");
+#endif
+ }
+
+ return 0;
+}
+
+void led_deinit()
+{
+ close(leds);
+
+ if (rgbleds != -1) {
+ close(rgbleds);
+ }
+}
+
+int led_toggle(int led)
+{
+ return ioctl(leds, LED_TOGGLE, led);
+}
+
+int led_on(int led)
+{
+ return ioctl(leds, LED_ON, led);
+}
+
+int led_off(int led)
+{
+ return ioctl(leds, LED_OFF, led);
+}
+
+void rgbled_set_color(rgbled_color_t color)
+{
+
+ if (rgbleds != -1)
+ ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
+}
+
+void rgbled_set_mode(rgbled_mode_t mode)
+{
+
+ if (rgbleds != -1)
+ ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
+}
+
+void rgbled_set_pattern(rgbled_pattern_t *pattern)
+{
+
+ if (rgbleds != -1)
+ ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
+}
+
+float battery_remaining_estimate_voltage(float voltage, float discharged)
+{
+ float ret = 0;
+ static param_t bat_v_empty_h;
+ static param_t bat_v_full_h;
+ static param_t bat_n_cells_h;
+ static param_t bat_capacity_h;
+ static float bat_v_empty = 3.2f;
+ static float bat_v_full = 4.0f;
+ static int bat_n_cells = 3;
+ static float bat_capacity = -1.0f;
+ static bool initialized = false;
+ static unsigned int counter = 0;
+
+ if (!initialized) {
+ bat_v_empty_h = param_find("BAT_V_EMPTY");
+ bat_v_full_h = param_find("BAT_V_FULL");
+ bat_n_cells_h = param_find("BAT_N_CELLS");
+ bat_capacity_h = param_find("BAT_CAPACITY");
+ initialized = true;
+ }
+
+ if (counter % 100 == 0) {
+ param_get(bat_v_empty_h, &bat_v_empty);
+ param_get(bat_v_full_h, &bat_v_full);
+ param_get(bat_n_cells_h, &bat_n_cells);
+ param_get(bat_capacity_h, &bat_capacity);
+ }
+
+ counter++;
+
+ /* remaining charge estimate based on voltage */
+ float remaining_voltage = (voltage - bat_n_cells * bat_v_empty) / (bat_n_cells * (bat_v_full - bat_v_empty));
+
+ if (bat_capacity > 0.0f) {
+ /* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */
+ ret = fminf(remaining_voltage, 1.0f - discharged / bat_capacity);
+ } else {
+ /* else use voltage */
+ ret = remaining_voltage;
+ }
+
+ /* limit to sane values */
+ ret = (ret < 0.0f) ? 0.0f : ret;
+ ret = (ret > 1.0f) ? 1.0f : ret;
+ return ret;
+}
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
new file mode 100644
index 000000000..af25a5e97
--- /dev/null
+++ b/src/modules/commander/commander_helper.h
@@ -0,0 +1,90 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 commander_helper.h
+ * Commander helper functions definitions
+ */
+
+#ifndef COMMANDER_HELPER_H_
+#define COMMANDER_HELPER_H_
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <drivers/drv_rgbled.h>
+
+
+bool is_multirotor(const struct vehicle_status_s *current_status);
+bool is_rotary_wing(const struct vehicle_status_s *current_status);
+
+int buzzer_init(void);
+void buzzer_deinit(void);
+
+void tune_error(void);
+void tune_positive(void);
+void tune_neutral(void);
+void tune_negative(void);
+int tune_arm(void);
+int tune_low_bat(void);
+int tune_critical_bat(void);
+void tune_stop(void);
+
+void led_negative();
+
+int blink_msg_state();
+
+int led_init(void);
+void led_deinit(void);
+int led_toggle(int led);
+int led_on(int led);
+int led_off(int led);
+
+void rgbled_set_color(rgbled_color_t color);
+void rgbled_set_mode(rgbled_mode_t mode);
+void rgbled_set_pattern(rgbled_pattern_t *pattern);
+
+/**
+ * Estimate remaining battery charge.
+ *
+ * Use integral of current if battery capacity known (BAT_CAPACITY parameter set),
+ * else use simple estimate based on voltage.
+ *
+ * @return the estimated remaining capacity in 0..1
+ */
+float battery_remaining_estimate_voltage(float voltage, float discharged);
+
+#endif /* COMMANDER_HELPER_H_ */
diff --git a/src/modules/commander/commander.h b/src/modules/commander/commander_params.c
index 04b4e72ab..e10b7f18d 100644
--- a/src/modules/commander/commander.h
+++ b/src/modules/commander/commander_params.c
@@ -1,10 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,23 +33,24 @@
****************************************************************************/
/**
- * @file commander.h
- * Main system state machine definition.
+ * @file commander_params.c
+ *
+ * Parameters defined by the sensors task.
*
- * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
- *
*/
-#ifndef COMMANDER_H_
-#define COMMANDER_H_
-
-#define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
-#define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
-
-void tune_confirm(void);
-void tune_error(void);
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
-#endif /* COMMANDER_H_ */
+PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 5.0f);
+PARAM_DEFINE_FLOAT(NAV_TAKEOFF_GAP, 3.0f);
+PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
+PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
+PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
+PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f);
+PARAM_DEFINE_FLOAT(BAT_V_FULL, 3.9f);
+PARAM_DEFINE_INT32(BAT_N_CELLS, 3);
+PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
diff --git a/src/modules/mathlib/math/Vector.hpp b/src/modules/commander/commander_tests/commander_tests.cpp
index 73de793d5..6e72cf0d9 100644
--- a/src/modules/mathlib/math/Vector.hpp
+++ b/src/modules/commander/commander_tests/commander_tests.cpp
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,26 +33,23 @@
****************************************************************************/
/**
- * @file Vector.h
+ * @file commander_tests.cpp
+ * Commander unit tests. Run the tests as follows:
+ * nsh> commander_tests
*
- * math vector
*/
-#pragma once
+#include <systemlib/err.h>
-#include <nuttx/config.h>
+#include "state_machine_helper_test.h"
-#if defined(CONFIG_ARCH_CORTEXM4) && defined(CONFIG_ARCH_FPU)
-#include "arm/Vector.hpp"
-#else
-#include "generic/Vector.hpp"
-#endif
+extern "C" __EXPORT int commander_tests_main(int argc, char *argv[]);
-namespace math
+
+int commander_tests_main(int argc, char *argv[])
{
-class Vector;
-int __EXPORT vectorTest();
-int __EXPORT vectorAddTest();
-int __EXPORT vectorSubTest();
-bool vectorEqual(const Vector &a, const Vector &b, float eps = 1.0e-5f);
-} // math
+ state_machine_helper_test();
+ //state_machine_test();
+
+ return 0;
+}
diff --git a/src/modules/mathlib/CMSIS/library.mk b/src/modules/commander/commander_tests/module.mk
index 0cc1b559d..4d10275d1 100644
--- a/src/modules/mathlib/CMSIS/library.mk
+++ b/src/modules/commander/commander_tests/module.mk
@@ -32,15 +32,10 @@
############################################################################
#
-# ARM CMSIS DSP library
+# System state machine tests.
#
-ifeq ($(CONFIG_ARCH),CORTEXM4F)
-PREBUILT_LIB := libarm_cortexM4lf_math.a
-else ifeq ($(CONFIG_ARCH),CORTEXM4)
-PREBUILT_LIB := libarm_cortexM4l_math.a
-else ifeq ($(CONFIG_ARCH),CORTEXM3)
-PREBUILT_LIB := libarm_cortexM3l_math.a
-else
-$(error CONFIG_ARCH value '$(CONFIG_ARCH)' not supported by the DSP library)
-endif
+MODULE_COMMAND = commander_tests
+SRCS = commander_tests.cpp \
+ state_machine_helper_test.cpp \
+ ../state_machine_helper.cpp
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
new file mode 100644
index 000000000..40bedd9f3
--- /dev/null
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -0,0 +1,247 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 state_machine_helper_test.cpp
+ * System state machine unit test.
+ *
+ */
+
+#include "state_machine_helper_test.h"
+
+#include "../state_machine_helper.h"
+#include <unit_test/unit_test.h>
+
+class StateMachineHelperTest : public UnitTest
+{
+public:
+ StateMachineHelperTest();
+ virtual ~StateMachineHelperTest();
+
+ virtual const char* run_tests();
+
+private:
+ const char* arming_state_transition_test();
+ const char* arming_state_transition_arm_disarm_test();
+ const char* main_state_transition_test();
+ const char* is_safe_test();
+};
+
+StateMachineHelperTest::StateMachineHelperTest() {
+}
+
+StateMachineHelperTest::~StateMachineHelperTest() {
+}
+
+const char*
+StateMachineHelperTest::arming_state_transition_test()
+{
+ struct vehicle_status_s status;
+ struct safety_s safety;
+ arming_state_t new_arming_state;
+ struct actuator_armed_s armed;
+
+ // Identical states.
+ status.arming_state = ARMING_STATE_INIT;
+ new_arming_state = ARMING_STATE_INIT;
+ mu_assert("no transition: identical states",
+ TRANSITION_NOT_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed));
+
+ // INIT to STANDBY.
+ armed.armed = false;
+ armed.ready_to_arm = false;
+ status.arming_state = ARMING_STATE_INIT;
+ status.condition_system_sensors_initialized = true;
+ new_arming_state = ARMING_STATE_STANDBY;
+ mu_assert("transition: init to standby",
+ TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed));
+ mu_assert("current state: standby", ARMING_STATE_STANDBY == status.arming_state);
+ mu_assert("not armed", !armed.armed);
+ mu_assert("ready to arm", armed.ready_to_arm);
+
+ // INIT to STANDBY, sensors not initialized.
+ armed.armed = false;
+ armed.ready_to_arm = false;
+ status.arming_state = ARMING_STATE_INIT;
+ status.condition_system_sensors_initialized = false;
+ new_arming_state = ARMING_STATE_STANDBY;
+ mu_assert("no transition: sensors not initialized",
+ TRANSITION_DENIED == arming_state_transition(&status, &safety, new_arming_state, &armed));
+ mu_assert("current state: init", ARMING_STATE_INIT == status.arming_state);
+ mu_assert("not armed", !armed.armed);
+ mu_assert("not ready to arm", !armed.ready_to_arm);
+
+ return 0;
+}
+
+const char*
+StateMachineHelperTest::arming_state_transition_arm_disarm_test()
+{
+ struct vehicle_status_s status;
+ struct safety_s safety;
+ arming_state_t new_arming_state;
+ struct actuator_armed_s armed;
+
+ // TODO(sjwilks): ARM then DISARM.
+ return 0;
+}
+
+const char*
+StateMachineHelperTest::main_state_transition_test()
+{
+ struct vehicle_status_s current_state;
+ main_state_t new_main_state;
+
+ // Identical states.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ new_main_state = MAIN_STATE_MANUAL;
+ mu_assert("no transition: identical states",
+ TRANSITION_NOT_CHANGED == main_state_transition(&current_state, new_main_state));
+ mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+
+ // AUTO to MANUAL.
+ current_state.main_state = MAIN_STATE_AUTO;
+ new_main_state = MAIN_STATE_MANUAL;
+ mu_assert("transition changed: auto to manual",
+ TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
+ mu_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+
+ // MANUAL to SEATBELT.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ current_state.condition_local_altitude_valid = true;
+ new_main_state = MAIN_STATE_SEATBELT;
+ mu_assert("tranisition: manual to seatbelt",
+ TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
+ mu_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
+
+ // MANUAL to SEATBELT, invalid local altitude.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ current_state.condition_local_altitude_valid = false;
+ new_main_state = MAIN_STATE_SEATBELT;
+ mu_assert("no transition: invalid local altitude",
+ TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
+ mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+
+ // MANUAL to EASY.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ current_state.condition_local_position_valid = true;
+ new_main_state = MAIN_STATE_EASY;
+ mu_assert("transition: manual to easy",
+ TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
+ mu_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
+
+ // MANUAL to EASY, invalid local position.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ current_state.condition_local_position_valid = false;
+ new_main_state = MAIN_STATE_EASY;
+ mu_assert("no transition: invalid position",
+ TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
+ mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+
+ // MANUAL to AUTO.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ current_state.condition_global_position_valid = true;
+ new_main_state = MAIN_STATE_AUTO;
+ mu_assert("transition: manual to auto",
+ TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
+ mu_assert("current state: auto", MAIN_STATE_AUTO == current_state.main_state);
+
+ // MANUAL to AUTO, invalid global position.
+ current_state.main_state = MAIN_STATE_MANUAL;
+ current_state.condition_global_position_valid = false;
+ new_main_state = MAIN_STATE_AUTO;
+ mu_assert("no transition: invalid global position",
+ TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
+ mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+
+ return 0;
+}
+
+const char*
+StateMachineHelperTest::is_safe_test()
+{
+ struct vehicle_status_s current_state;
+ struct safety_s safety;
+ struct actuator_armed_s armed;
+
+ armed.armed = false;
+ armed.lockdown = false;
+ safety.safety_switch_available = true;
+ safety.safety_off = false;
+ mu_assert("is safe: not armed", is_safe(&current_state, &safety, &armed));
+
+ armed.armed = false;
+ armed.lockdown = true;
+ safety.safety_switch_available = true;
+ safety.safety_off = true;
+ mu_assert("is safe: software lockdown", is_safe(&current_state, &safety, &armed));
+
+ armed.armed = true;
+ armed.lockdown = false;
+ safety.safety_switch_available = true;
+ safety.safety_off = true;
+ mu_assert("not safe: safety off", !is_safe(&current_state, &safety, &armed));
+
+ armed.armed = true;
+ armed.lockdown = false;
+ safety.safety_switch_available = true;
+ safety.safety_off = false;
+ mu_assert("is safe: safety off", is_safe(&current_state, &safety, &armed));
+
+ armed.armed = true;
+ armed.lockdown = false;
+ safety.safety_switch_available = false;
+ safety.safety_off = false;
+ mu_assert("not safe: no safety switch", !is_safe(&current_state, &safety, &armed));
+
+ return 0;
+}
+
+const char*
+StateMachineHelperTest::run_tests()
+{
+ mu_run_test(arming_state_transition_test);
+ mu_run_test(arming_state_transition_arm_disarm_test);
+ mu_run_test(main_state_transition_test);
+ mu_run_test(is_safe_test);
+
+ return 0;
+}
+
+void
+state_machine_helper_test()
+{
+ StateMachineHelperTest* test = new StateMachineHelperTest();
+ test->UnitTest::print_results(test->run_tests());
+}
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.h b/src/modules/commander/commander_tests/state_machine_helper_test.h
new file mode 100644
index 000000000..10a68e602
--- /dev/null
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.h
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 state_machine_helper_test.h
+ */
+
+#ifndef STATE_MACHINE_HELPER_TEST_H_
+#define STATE_MACHINE_HELPER_TEST_
+
+void state_machine_helper_test();
+
+#endif /* STATE_MACHINE_HELPER_TEST_H_ */
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
new file mode 100644
index 000000000..30cd0d48d
--- /dev/null
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -0,0 +1,305 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 gyro_calibration.cpp
+ *
+ * Gyroscope calibration routine
+ */
+
+#include "gyro_calibration.h"
+#include "calibration_messages.h"
+#include "commander_helper.h"
+
+#include <stdio.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <math.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_gyro.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+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");
+
+ struct gyro_scale gyro_scale = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ int res = OK;
+
+ /* reset all offsets to zero and all scales to one */
+ int fd = open(GYRO_DEVICE_PATH, 0);
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
+ close(fd);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
+
+ if (res == OK) {
+ /* determine gyro mean values */
+ const unsigned calibration_count = 5000;
+ unsigned calibration_counter = 0;
+ unsigned poll_errcount = 0;
+
+ /* subscribe to gyro sensor topic */
+ int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
+ struct gyro_report gyro_report;
+
+ while (calibration_counter < calibration_count) {
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_gyro;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_gyro), sub_sensor_gyro, &gyro_report);
+ gyro_scale.x_offset += gyro_report.x;
+ gyro_scale.y_offset += gyro_report.y;
+ gyro_scale.z_offset += gyro_report.z;
+ calibration_counter++;
+
+ if (calibration_counter % (calibration_count / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
+ }
+
+ close(sub_sensor_gyro);
+
+ gyro_scale.x_offset /= calibration_count;
+ gyro_scale.y_offset /= calibration_count;
+ gyro_scale.z_offset /= calibration_count;
+ }
+
+ if (res == OK) {
+ /* check offsets */
+ if (!isfinite(gyro_scale.x_offset) || !isfinite(gyro_scale.y_offset) || !isfinite(gyro_scale.z_offset)) {
+ mavlink_log_critical(mavlink_fd, "ERROR: offset is NaN");
+ res = ERROR;
+ }
+ }
+
+ if (res == OK) {
+ /* set offset parameters to new values */
+ if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_scale.x_offset))
+ || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_scale.y_offset))
+ || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_scale.z_offset))) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set offset params");
+ res = ERROR;
+ }
+ }
+
+#if 0
+ /* beep on offset calibration end */
+ mavlink_log_info(mavlink_fd, "gyro offset calibration done");
+ tune_neutral();
+
+ /* scale calibration */
+ /* this was only a proof of concept and is currently not working. scaling will be set to 1.0 for now. */
+
+ mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
+ warnx("offset calibration finished. Rotate for scale 30x, or do not rotate and wait for 5 seconds to skip.");
+
+ /* apply new offsets */
+ fd = open(GYRO_DEVICE_PATH, 0);
+
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ warn("WARNING: failed to apply new offsets for gyro");
+
+ close(fd);
+
+
+ unsigned rotations_count = 30;
+ float gyro_integral = 0.0f;
+ float baseline_integral = 0.0f;
+
+ // XXX change to mag topic
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
+
+ float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
+
+ if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+
+ if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
+
+
+ uint64_t last_time = hrt_absolute_time();
+ uint64_t start_time = hrt_absolute_time();
+
+ while ((int)fabsf(baseline_integral / (2.0f * M_PI_F)) < rotations_count) {
+
+ /* abort this loop if not rotated more than 180 degrees within 5 seconds */
+ if ((fabsf(baseline_integral / (2.0f * M_PI_F)) < 0.6f)
+ && (hrt_absolute_time() - start_time > 5 * 1e6)) {
+ mavlink_log_info(mavlink_fd, "scale skipped, gyro calibration done");
+ close(sub_sensor_combined);
+ return OK;
+ }
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_combined;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+
+ float dt_ms = (hrt_absolute_time() - last_time) / 1e3f;
+ last_time = hrt_absolute_time();
+
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
+
+ // XXX this is just a proof of concept and needs world / body
+ // transformation and more
+
+ //math::Vector2f magNav(raw.magnetometer_ga);
+
+ // calculate error between estimate and measurement
+ // apply declination correction for true heading as well.
+ //float mag = -atan2f(magNav(1),magNav(0));
+ float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
+
+ if (mag > M_PI_F) mag -= 2 * M_PI_F;
+
+ if (mag < -M_PI_F) mag += 2 * M_PI_F;
+
+ float diff = mag - mag_last;
+
+ if (diff > M_PI_F) diff -= 2 * M_PI_F;
+
+ if (diff < -M_PI_F) diff += 2 * M_PI_F;
+
+ baseline_integral += diff;
+ mag_last = mag;
+ // Jump through some timing scale hoops to avoid
+ // operating near the 1e6/1e8 max sane resolution of float.
+ gyro_integral += (raw.gyro_rad_s[2] * dt_ms) / 1e3f;
+
+// warnx("dbg: b: %6.4f, g: %6.4f", (double)baseline_integral, (double)gyro_integral);
+
+ // } else if (poll_ret == 0) {
+ // /* any poll failure for 1s is a reason to abort */
+ // mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
+ // return;
+ }
+ }
+
+ float gyro_scale = baseline_integral / gyro_integral;
+
+ warnx("gyro scale: yaw (z): %6.4f", (double)gyro_scale);
+ mavlink_log_info(mavlink_fd, "gyro scale: yaw (z): %6.4f", (double)gyro_scale);
+
+
+ if (!isfinite(gyro_scale.x_scale) || !isfinite(gyro_scale.y_scale) || !isfinite(gyro_scale.z_scale)) {
+ mavlink_log_info(mavlink_fd, "gyro scale calibration FAILED (NaN)");
+ close(sub_sensor_gyro);
+ mavlink_log_critical(mavlink_fd, "gyro calibration failed");
+ return ERROR;
+ }
+
+ /* beep on calibration end */
+ mavlink_log_info(mavlink_fd, "gyro scale calibration done");
+ tune_neutral();
+
+#endif
+
+ if (res == OK) {
+ /* set scale parameters to new values */
+ if (param_set(param_find("SENS_GYRO_XSCALE"), &(gyro_scale.x_scale))
+ || param_set(param_find("SENS_GYRO_YSCALE"), &(gyro_scale.y_scale))
+ || param_set(param_find("SENS_GYRO_ZSCALE"), &(gyro_scale.z_scale))) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set scale params");
+ res = ERROR;
+ }
+ }
+
+ if (res == OK) {
+ /* apply new scaling and offsets */
+ fd = open(GYRO_DEVICE_PATH, 0);
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
+ close(fd);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
+ }
+
+ if (res == OK) {
+ /* auto-save to EEPROM */
+ res = param_save_default();
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
+ }
+ }
+
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
+
+ } else {
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ }
+
+ return res;
+}
diff --git a/src/modules/mathlib/math/arm/Matrix.cpp b/src/modules/commander/gyro_calibration.h
index 21661622a..59c32a15e 100644
--- a/src/modules/mathlib/math/arm/Matrix.cpp
+++ b/src/modules/commander/gyro_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 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
@@ -32,9 +32,15 @@
****************************************************************************/
/**
- * @file Matrix.cpp
- *
- * matrix code
+ * @file gyro_calibration.h
+ * Gyroscope calibration routine
*/
-#include "Matrix.hpp"
+#ifndef GYRO_CALIBRATION_H_
+#define GYRO_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_gyro_calibration(int mavlink_fd);
+
+#endif /* GYRO_CALIBRATION_H_ */
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
new file mode 100644
index 000000000..4ebf266f4
--- /dev/null
+++ b/src/modules/commander/mag_calibration.cpp
@@ -0,0 +1,285 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 mag_calibration.cpp
+ *
+ * Magnetometer calibration routine
+ */
+
+#include "mag_calibration.h"
+#include "commander_helper.h"
+#include "calibration_routines.h"
+#include "calibration_messages.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <poll.h>
+#include <math.h>
+#include <fcntl.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_mag.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+static const char *sensor_name = "mag";
+
+int do_mag_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
+
+ /* 45 seconds */
+ uint64_t calibration_interval = 45 * 1000 * 1000;
+
+ /* maximum 500 values */
+ const unsigned int calibration_maxcount = 500;
+ unsigned int calibration_counter;
+
+ struct mag_scale mscale_null = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ int res = OK;
+
+ /* erase old calibration */
+ int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
+
+ if (res == OK) {
+ /* calibrate range */
+ res = ioctl(fd, MAGIOCCALIBRATE, fd);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "Skipped scale calibration");
+ /* this is non-fatal - mark it accordingly */
+ res = OK;
+ }
+ }
+
+ close(fd);
+
+ float *x = NULL;
+ float *y = NULL;
+ float *z = NULL;
+
+ if (res == OK) {
+ /* allocate memory */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
+
+ x = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+ y = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+ z = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+
+ if (x == NULL || y == NULL || z == NULL) {
+ mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+ res = ERROR;
+ return res;
+ }
+ } else {
+ /* exit */
+ return ERROR;
+ }
+
+ if (res == OK) {
+ int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
+ struct mag_report mag;
+
+ /* limit update rate to get equally spaced measurements over time (in ms) */
+ orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
+
+ /* calibrate offsets */
+ 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");
+
+ calibration_counter = 0;
+
+ while (hrt_absolute_time() < calibration_deadline &&
+ calibration_counter < calibration_maxcount) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_mag;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
+
+ x[calibration_counter] = mag.x;
+ y[calibration_counter] = mag.y;
+ z[calibration_counter] = mag.z;
+
+ calibration_counter++;
+
+ if (calibration_counter % (calibration_maxcount / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
+ }
+
+ close(sub_mag);
+ }
+
+ float sphere_x;
+ float sphere_y;
+ float sphere_z;
+ float sphere_radius;
+
+ if (res == OK) {
+
+ /* sphere fit */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
+ sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 80);
+
+ if (!isfinite(sphere_x) || !isfinite(sphere_y) || !isfinite(sphere_z)) {
+ mavlink_log_critical(mavlink_fd, "ERROR: NaN in sphere fit");
+ res = ERROR;
+ }
+ }
+
+ if (x != NULL)
+ free(x);
+
+ if (y != NULL)
+ free(y);
+
+ if (z != NULL)
+ free(z);
+
+ if (res == OK) {
+ /* apply calibration and set parameters */
+ struct mag_scale mscale;
+
+ fd = open(MAG_DEVICE_PATH, 0);
+ res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to get current calibration");
+ }
+
+ if (res == OK) {
+ mscale.x_offset = sphere_x;
+ mscale.y_offset = sphere_y;
+ mscale.z_offset = sphere_z;
+
+ res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
+ }
+
+ close(fd);
+
+ if (res == OK) {
+ /* set parameters */
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ res = ERROR;
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ }
+
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 90);
+ }
+
+ if (res == OK) {
+ /* auto-save to EEPROM */
+ res = param_save_default();
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
+ }
+ }
+
+ mavlink_log_info(mavlink_fd, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
+ (double)mscale.y_offset, (double)mscale.z_offset);
+ mavlink_log_info(mavlink_fd, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
+ (double)mscale.y_scale, (double)mscale.z_scale);
+
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
+
+ } else {
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ }
+ }
+
+ return res;
+}
diff --git a/src/modules/mathlib/math/generic/Vector.cpp b/src/modules/commander/mag_calibration.h
index 7ea6496bb..a101cd7b1 100644
--- a/src/modules/mathlib/math/generic/Vector.cpp
+++ b/src/modules/commander/mag_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 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
@@ -32,9 +32,15 @@
****************************************************************************/
/**
- * @file Vector.cpp
- *
- * math vector
+ * @file mag_calibration.h
+ * Magnetometer calibration routine
*/
-#include "Vector.hpp"
+#ifndef MAG_CALIBRATION_H_
+#define MAG_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_mag_calibration(int mavlink_fd);
+
+#endif /* MAG_CALIBRATION_H_ */
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index fe44e955a..554dfcb08 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -36,8 +36,14 @@
#
MODULE_COMMAND = commander
-SRCS = commander.c \
- state_machine_helper.c \
- calibration_routines.c \
- accelerometer_calibration.c
-
+SRCS = commander.cpp \
+ commander_params.c \
+ state_machine_helper.cpp \
+ commander_helper.cpp \
+ calibration_routines.cpp \
+ accelerometer_calibration.cpp \
+ gyro_calibration.cpp \
+ mag_calibration.cpp \
+ baro_calibration.cpp \
+ rc_calibration.cpp \
+ airspeed_calibration.cpp
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
new file mode 100644
index 000000000..b60a7e0b9
--- /dev/null
+++ b/src/modules/commander/px4_custom_mode.h
@@ -0,0 +1,37 @@
+/*
+ * px4_custom_mode.h
+ *
+ * Created on: 09.08.2013
+ * Author: ton
+ */
+
+#ifndef PX4_CUSTOM_MODE_H_
+#define PX4_CUSTOM_MODE_H_
+
+enum PX4_CUSTOM_MAIN_MODE {
+ PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
+ PX4_CUSTOM_MAIN_MODE_SEATBELT,
+ PX4_CUSTOM_MAIN_MODE_EASY,
+ PX4_CUSTOM_MAIN_MODE_AUTO,
+};
+
+enum PX4_CUSTOM_SUB_MODE_AUTO {
+ PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
+ PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
+ PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
+ PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
+ PX4_CUSTOM_SUB_MODE_AUTO_RTL,
+ PX4_CUSTOM_SUB_MODE_AUTO_LAND,
+};
+
+union px4_custom_mode {
+ struct {
+ uint16_t reserved;
+ uint8_t main_mode;
+ uint8_t sub_mode;
+ };
+ uint32_t data;
+ float data_float;
+};
+
+#endif /* PX4_CUSTOM_MODE_H_ */
diff --git a/src/modules/mathlib/math/Vector.cpp b/src/modules/commander/rc_calibration.cpp
index 35158a396..41f3ca0aa 100644
--- a/src/modules/mathlib/math/Vector.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 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
@@ -32,69 +32,61 @@
****************************************************************************/
/**
- * @file Vector.cpp
- *
- * math vector
+ * @file rc_calibration.cpp
+ * Remote Control calibration routine
*/
-#include "test/test.hpp"
-
-#include "Vector.hpp"
-
-namespace math
-{
+#include "rc_calibration.h"
+#include "commander_helper.h"
-static const float data_testA[] = {1, 3};
-static const float data_testB[] = {4, 1};
+#include <poll.h>
+#include <unistd.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
-static Vector testA(2, data_testA);
-static Vector testB(2, data_testB);
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
-int __EXPORT vectorTest()
+int do_trim_calibration(int mavlink_fd)
{
- vectorAddTest();
- vectorSubTest();
- return 0;
-}
+ int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
+ usleep(200000);
+ struct manual_control_setpoint_s sp;
+ bool changed;
+ orb_check(sub_man, &changed);
-int vectorAddTest()
-{
- printf("Test Vector Add\t\t: ");
- Vector r = testA + testB;
- float data_test[] = {5.0f, 4.0f};
- ASSERT(vectorEqual(Vector(2, data_test), r));
- printf("PASS\n");
- return 0;
-}
+ if (!changed) {
+ mavlink_log_critical(mavlink_fd, "no inputs, aborting");
+ return ERROR;
+ }
-int vectorSubTest()
-{
- printf("Test Vector Sub\t\t: ");
- Vector r(2);
- r = testA - testB;
- float data_test[] = { -3.0f, 2.0f};
- ASSERT(vectorEqual(Vector(2, data_test), r));
- printf("PASS\n");
- return 0;
-}
+ orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
-bool vectorEqual(const Vector &a, const Vector &b, float eps)
-{
- if (a.getRows() != b.getRows()) {
- printf("row number not equal a: %d, b:%d\n", a.getRows(), b.getRows());
- return false;
- }
+ /* set parameters */
+ float p = sp.roll;
+ param_set(param_find("TRIM_ROLL"), &p);
+ p = sp.pitch;
+ param_set(param_find("TRIM_PITCH"), &p);
+ p = sp.yaw;
+ param_set(param_find("TRIM_YAW"), &p);
- bool ret = true;
+ /* store to permanent storage */
+ /* auto-save */
+ int save_ret = param_save_default();
- for (size_t i = 0; i < a.getRows(); i++) {
- if (!equal(a(i), b(i), eps)) {
- printf("element mismatch (%d)\n", i);
- ret = false;
- }
+ if (save_ret != 0) {
+ mavlink_log_critical(mavlink_fd, "TRIM: SAVE FAIL");
+ close(sub_man);
+ return ERROR;
}
- return ret;
+ mavlink_log_info(mavlink_fd, "trim cal done");
+ close(sub_man);
+ return OK;
}
-
-} // namespace math
diff --git a/src/modules/mathlib/math/arm/Vector.cpp b/src/modules/commander/rc_calibration.h
index 7ea6496bb..45efedf55 100644
--- a/src/modules/mathlib/math/arm/Vector.cpp
+++ b/src/modules/commander/rc_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 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
@@ -32,9 +32,15 @@
****************************************************************************/
/**
- * @file Vector.cpp
- *
- * math vector
+ * @file rc_calibration.h
+ * Remote Control calibration routine
*/
-#include "Vector.hpp"
+#ifndef RC_CALIBRATION_H_
+#define RC_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_trim_calibration(int mavlink_fd);
+
+#endif /* RC_CALIBRATION_H_ */
diff --git a/src/modules/commander/state_machine_helper.c b/src/modules/commander/state_machine_helper.c
deleted file mode 100644
index ab728c7bb..000000000
--- a/src/modules/commander/state_machine_helper.c
+++ /dev/null
@@ -1,757 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- *
- * 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 state_machine_helper.c
- * State machine helper functions implementations
- */
-
-#include <stdio.h>
-#include <unistd.h>
-
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/actuator_controls.h>
-#include <systemlib/systemlib.h>
-#include <drivers/drv_hrt.h>
-#include <mavlink/mavlink_log.h>
-
-#include "state_machine_helper.h"
-
-static const char *system_state_txt[] = {
- "SYSTEM_STATE_PREFLIGHT",
- "SYSTEM_STATE_STANDBY",
- "SYSTEM_STATE_GROUND_READY",
- "SYSTEM_STATE_MANUAL",
- "SYSTEM_STATE_STABILIZED",
- "SYSTEM_STATE_AUTO",
- "SYSTEM_STATE_MISSION_ABORT",
- "SYSTEM_STATE_EMCY_LANDING",
- "SYSTEM_STATE_EMCY_CUTOFF",
- "SYSTEM_STATE_GROUND_ERROR",
- "SYSTEM_STATE_REBOOT",
-
-};
-
-/**
- * Transition from one state to another
- */
-int do_state_update(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, commander_state_machine_t new_state)
-{
- int invalid_state = false;
- int ret = ERROR;
-
- commander_state_machine_t old_state = current_status->state_machine;
-
- switch (new_state) {
- case SYSTEM_STATE_MISSION_ABORT: {
- /* Indoor or outdoor */
- // if (flight_environment_parameter == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
- ret = do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_EMCY_LANDING);
-
- // } else {
- // ret = do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_EMCY_CUTOFF);
- // }
- }
- break;
-
- case SYSTEM_STATE_EMCY_LANDING:
- /* Tell the controller to land */
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- warnx("EMERGENCY LANDING!\n");
- mavlink_log_critical(mavlink_fd, "EMERGENCY LANDING!");
- break;
-
- case SYSTEM_STATE_EMCY_CUTOFF:
- /* Tell the controller to cutoff the motors (thrust = 0) */
-
- /* set system flags according to state */
- current_status->flag_system_armed = false;
-
- warnx("EMERGENCY MOTOR CUTOFF!\n");
- mavlink_log_critical(mavlink_fd, "EMERGENCY MOTOR CUTOFF!");
- break;
-
- case SYSTEM_STATE_GROUND_ERROR:
-
- /* set system flags according to state */
-
- /* prevent actuators from arming */
- current_status->flag_system_armed = false;
-
- warnx("GROUND ERROR, locking down propulsion system\n");
- mavlink_log_critical(mavlink_fd, "GROUND ERROR, locking down system");
- break;
-
- case SYSTEM_STATE_PREFLIGHT:
- if (current_status->state_machine == SYSTEM_STATE_STANDBY
- || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- /* set system flags according to state */
- current_status->flag_system_armed = false;
- mavlink_log_critical(mavlink_fd, "Switched to PREFLIGHT state");
-
- } else {
- invalid_state = true;
- mavlink_log_critical(mavlink_fd, "REFUSED to switch to PREFLIGHT state");
- }
-
- break;
-
- case SYSTEM_STATE_REBOOT:
- if (current_status->state_machine == SYSTEM_STATE_STANDBY
- || current_status->state_machine == SYSTEM_STATE_PREFLIGHT
- || current_status->flag_hil_enabled) {
- invalid_state = false;
- /* set system flags according to state */
- current_status->flag_system_armed = false;
- mavlink_log_critical(mavlink_fd, "REBOOTING SYSTEM");
- usleep(500000);
- up_systemreset();
- /* SPECIAL CASE: NEVER RETURNS FROM THIS FUNCTION CALL */
-
- } else {
- invalid_state = true;
- mavlink_log_critical(mavlink_fd, "REFUSED to REBOOT");
- }
-
- break;
-
- case SYSTEM_STATE_STANDBY:
- /* set system flags according to state */
-
- /* standby enforces disarmed */
- current_status->flag_system_armed = false;
-
- mavlink_log_critical(mavlink_fd, "Switched to STANDBY state");
- break;
-
- case SYSTEM_STATE_GROUND_READY:
-
- /* set system flags according to state */
-
- /* ground ready has motors / actuators armed */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to GROUND READY state");
- break;
-
- case SYSTEM_STATE_AUTO:
-
- /* set system flags according to state */
-
- /* auto is airborne and in auto mode, motors armed */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / AUTO mode");
- break;
-
- case SYSTEM_STATE_STABILIZED:
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / STABILIZED mode");
- break;
-
- case SYSTEM_STATE_MANUAL:
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / MANUAL mode");
- break;
-
- default:
- invalid_state = true;
- break;
- }
-
- if (invalid_state == false || old_state != new_state) {
- current_status->state_machine = new_state;
- state_machine_publish(status_pub, current_status, mavlink_fd);
- publish_armed_status(current_status);
- ret = OK;
- }
-
- if (invalid_state) {
- mavlink_log_critical(mavlink_fd, "REJECTING invalid state transition");
- ret = ERROR;
- }
-
- return ret;
-}
-
-void state_machine_publish(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* publish the new state */
- current_status->counter++;
- current_status->timestamp = hrt_absolute_time();
-
- /* assemble state vector based on flag values */
- if (current_status->flag_control_rates_enabled) {
- current_status->onboard_control_sensors_present |= 0x400;
-
- } else {
- current_status->onboard_control_sensors_present &= ~0x400;
- }
-
- current_status->onboard_control_sensors_present |= (current_status->flag_control_attitude_enabled) ? 0x800 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_attitude_enabled) ? 0x1000 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x2000 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0;
-
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_rates_enabled) ? 0x400 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_attitude_enabled) ? 0x800 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_attitude_enabled) ? 0x1000 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x2000 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0;
-
- orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
- printf("[cmd] new state: %s\n", system_state_txt[current_status->state_machine]);
-}
-
-void publish_armed_status(const struct vehicle_status_s *current_status)
-{
- struct actuator_armed_s armed;
- armed.armed = current_status->flag_system_armed;
-
- /* XXX allow arming by external components on multicopters only if not yet armed by RC */
- /* XXX allow arming only if core sensors are ok */
- armed.ready_to_arm = true;
-
- /* lock down actuators if required, only in HIL */
- armed.lockdown = (current_status->flag_hil_enabled) ? true : false;
- orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
- orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
-}
-
-
-/*
- * Private functions, update the state machine
- */
-void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- warnx("EMERGENCY HANDLER\n");
- /* Depending on the current state go to one of the error states */
-
- if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT || current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_ERROR);
-
- } else if (current_status->state_machine == SYSTEM_STATE_AUTO || current_status->state_machine == SYSTEM_STATE_MANUAL) {
-
- // DO NOT abort mission
- //do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MISSION_ABORT);
-
- } else {
- warnx("Unknown system state: #%d\n", current_status->state_machine);
- }
-}
-
-void state_machine_emergency(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) //do not call state_machine_emergency_always_critical if we are in manual mode for these errors
-{
- if (current_status->state_machine != SYSTEM_STATE_MANUAL) { //if we are in manual: user can react to errors themself
- state_machine_emergency_always_critical(status_pub, current_status, mavlink_fd);
-
- } else {
- //global_data_send_mavlink_statustext_message_out("[cmd] ERROR: take action immediately! (did not switch to error state because the system is in manual mode)", MAV_SEVERITY_CRITICAL);
- }
-
-}
-
-
-
-// /*
-// * Wrapper functions (to be used in the commander), all functions assume lock on current_status
-// */
-
-// /* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR
-// *
-// * START SUBSYSTEM/EMERGENCY FUNCTIONS
-// * */
-
-// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_present |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-// }
-
-// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_present &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if a subsystem was removed something went completely wrong */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: gyro not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// {
-// uint8_t flight_env = global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV];
-
-// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
-// //global_data_send_mavlink_statustext_message_out("Commander: GPS not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency(status_pub, current_status);
-// }
-// }
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_enabled |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-// }
-
-// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_enabled &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if a subsystem was disabled something went completely wrong */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - gyro disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - accelerometer disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - magnetometer disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// {
-// uint8_t flight_env = (uint8_t)(global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV]);
-
-// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - GPS disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency(status_pub, current_status);
-// }
-// }
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-
-// void update_state_machine_subsystem_healthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_health |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //TODO state machine change (recovering)
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //TODO state machine change
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //TODO state machine change
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// //TODO state machine change
-// break;
-
-// default:
-// break;
-// }
-
-
-// }
-
-
-// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// bool previosly_healthy = (bool)(current_status->onboard_control_sensors_health & 1 << *subsystem_type);
-// current_status->onboard_control_sensors_health &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if we received unhealthy message more than *_HEALTH_COUNTER_LIMIT, switch to error state */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: gyro unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// // //TODO: remove this block
-// // break;
-// // ///////////////////
-// //global_data_send_mavlink_statustext_message_out("Commander: GPS unhealthy", MAV_SEVERITY_CRITICAL);
-
-// // printf("previosly_healthy = %u\n", previosly_healthy);
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency(status_pub, current_status);
-
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-
-/* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
-
-
-void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* Depending on the current state switch state */
- if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- }
-}
-
-void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* Depending on the current state switch state */
- if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_AUTO) {
- state_machine_emergency(status_pub, current_status, mavlink_fd);
- }
-}
-
-void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_STANDBY) {
- printf("[cmd] arming\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
- }
-}
-
-void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- printf("[cmd] going standby\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
-
- } else if (current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] MISSION ABORT!\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- }
-}
-
-void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
-
- current_status->flag_control_manual_enabled = true;
-
- /* set behaviour based on airframe */
- if ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- /* assuming a rotary wing, set to SAS */
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
-
- } else {
-
- /* assuming a fixed wing, set to direct pass-through */
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- current_status->flag_control_attitude_enabled = false;
- current_status->flag_control_rates_enabled = false;
- }
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] manual mode\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- }
-}
-
-void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) {
- int old_mode = current_status->flight_mode;
- int old_manual_control_mode = current_status->manual_control_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- current_status->flag_control_manual_enabled = true;
-
- if (old_mode != current_status->flight_mode ||
- old_manual_control_mode != current_status->manual_control_mode) {
- printf("[cmd] att stabilized mode\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- state_machine_publish(status_pub, current_status, mavlink_fd);
- }
-
- }
-}
-
-void update_state_machine_mode_guided(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (!current_status->flag_vector_flight_mode_ok) {
- mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. GUIDED MODE");
- tune_error();
- return;
- }
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] position guided mode\n");
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_STAB;
- current_status->flag_control_manual_enabled = false;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STABILIZED);
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
-
- }
-}
-
-void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (!current_status->flag_vector_flight_mode_ok) {
- mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. AUTO MODE");
- return;
- }
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_STABILIZED) {
- printf("[cmd] auto mode\n");
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO;
- current_status->flag_control_manual_enabled = false;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO);
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
- }
-}
-
-
-uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
-{
- uint8_t ret = 1;
-
- /* Switch on HIL if in standby and not already in HIL mode */
- if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED)
- && !current_status->flag_hil_enabled) {
- if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) {
- /* Enable HIL on request */
- current_status->flag_hil_enabled = true;
- ret = OK;
- state_machine_publish(status_pub, current_status, mavlink_fd);
- publish_armed_status(current_status);
- printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n");
-
- } else if (current_status->state_machine != SYSTEM_STATE_STANDBY &&
- current_status->flag_system_armed) {
-
- mavlink_log_critical(mavlink_fd, "REJECTING HIL, disarm first!")
-
- } else {
-
- mavlink_log_critical(mavlink_fd, "REJECTING HIL, not in standby.")
- }
- }
-
- /* switch manual / auto */
- if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) {
- update_state_machine_mode_auto(status_pub, current_status, mavlink_fd);
-
- } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) {
- update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd);
-
- } else if (mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED) {
- update_state_machine_mode_guided(status_pub, current_status, mavlink_fd);
-
- } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) {
- update_state_machine_mode_manual(status_pub, current_status, mavlink_fd);
- }
-
- /* vehicle is disarmed, mode requests arming */
- if (!(current_status->flag_system_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- /* only arm in standby state */
- // XXX REMOVE
- if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
- ret = OK;
- printf("[cmd] arming due to command request\n");
- }
- }
-
- /* vehicle is armed, mode requests disarming */
- if (current_status->flag_system_armed && !(mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- /* only disarm in ground ready */
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- ret = OK;
- printf("[cmd] disarming due to command request\n");
- }
- }
-
- /* NEVER actually switch off HIL without reboot */
- if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) {
- warnx("DENYING request to switch off HIL. Please power cycle (safety reasons)\n");
- mavlink_log_critical(mavlink_fd, "Power-cycle to exit HIL");
- ret = ERROR;
- }
-
- return ret;
-}
-
-uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t custom_mode) //TODO: add more checks to avoid state switching in critical situations
-{
- commander_state_machine_t current_system_state = current_status->state_machine;
-
- uint8_t ret = 1;
-
- switch (custom_mode) {
- case SYSTEM_STATE_GROUND_READY:
- break;
-
- case SYSTEM_STATE_STANDBY:
- break;
-
- case SYSTEM_STATE_REBOOT:
- printf("try to reboot\n");
-
- if (current_system_state == SYSTEM_STATE_STANDBY
- || current_system_state == SYSTEM_STATE_PREFLIGHT
- || current_status->flag_hil_enabled) {
- printf("system will reboot\n");
- mavlink_log_critical(mavlink_fd, "Rebooting..");
- usleep(200000);
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_REBOOT);
- ret = 0;
- }
-
- break;
-
- case SYSTEM_STATE_AUTO:
- printf("try to switch to auto/takeoff\n");
-
- if (current_system_state == SYSTEM_STATE_GROUND_READY || current_system_state == SYSTEM_STATE_MANUAL) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO);
- printf("state: auto\n");
- ret = 0;
- }
-
- break;
-
- case SYSTEM_STATE_MANUAL:
- printf("try to switch to manual\n");
-
- if (current_system_state == SYSTEM_STATE_GROUND_READY || current_system_state == SYSTEM_STATE_AUTO) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- printf("state: manual\n");
- ret = 0;
- }
-
- break;
-
- default:
- break;
- }
-
- return ret;
-}
-
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
new file mode 100644
index 000000000..7ae61d9ef
--- /dev/null
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -0,0 +1,738 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 state_machine_helper.cpp
+ * State machine helper functions implementations
+ */
+
+#include <stdio.h>
+#include <unistd.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <dirent.h>
+#include <fcntl.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_device.h>
+#include <mavlink/mavlink_log.h>
+
+#include "state_machine_helper.h"
+#include "commander_helper.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+static bool arming_state_changed = true;
+static bool main_state_changed = true;
+static bool navigation_state_changed = true;
+
+transition_result_t
+arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety,
+ const struct vehicle_control_mode_s *control_mode,
+ arming_state_t new_arming_state, struct actuator_armed_s *armed)
+{
+ /*
+ * Perform an atomic state update
+ */
+ irqstate_t flags = irqsave();
+
+ transition_result_t ret = TRANSITION_DENIED;
+
+ /* only check transition if the new state is actually different from the current one */
+ if (new_arming_state == status->arming_state) {
+ ret = TRANSITION_NOT_CHANGED;
+
+ } else {
+
+ /* enforce lockdown in HIL */
+ if (control_mode->flag_system_hil_enabled) {
+ armed->lockdown = true;
+ } else {
+ armed->lockdown = false;
+ }
+
+ switch (new_arming_state) {
+ case ARMING_STATE_INIT:
+
+ /* allow going back from INIT for calibration */
+ if (status->arming_state == ARMING_STATE_STANDBY) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_STANDBY:
+
+ /* allow coming from INIT and disarming from ARMED */
+ if (status->arming_state == ARMING_STATE_INIT
+ || status->arming_state == ARMING_STATE_ARMED
+ || control_mode->flag_system_hil_enabled) {
+
+ /* sensors need to be initialized for STANDBY state */
+ if (status->condition_system_sensors_initialized) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = true;
+ }
+ }
+
+ break;
+
+ case ARMING_STATE_ARMED:
+
+ /* allow arming from STANDBY and IN-AIR-RESTORE */
+ if ((status->arming_state == ARMING_STATE_STANDBY
+ || status->arming_state == ARMING_STATE_IN_AIR_RESTORE)
+ && (!safety->safety_switch_available || safety->safety_off || control_mode->flag_system_hil_enabled)) { /* only allow arming if safety is off */
+ ret = TRANSITION_CHANGED;
+ armed->armed = true;
+ armed->ready_to_arm = true;
+ }
+
+ break;
+
+ case ARMING_STATE_ARMED_ERROR:
+
+ /* an armed error happens when ARMED obviously */
+ if (status->arming_state == ARMING_STATE_ARMED) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = true;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_STANDBY_ERROR:
+
+ /* a disarmed error happens when in STANDBY or in INIT or after ARMED_ERROR */
+ if (status->arming_state == ARMING_STATE_STANDBY
+ || status->arming_state == ARMING_STATE_INIT
+ || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_REBOOT:
+
+ /* an armed error happens when ARMED obviously */
+ if (status->arming_state == ARMING_STATE_INIT
+ || status->arming_state == ARMING_STATE_STANDBY
+ || status->arming_state == ARMING_STATE_STANDBY_ERROR) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_IN_AIR_RESTORE:
+
+ /* XXX implement */
+ break;
+
+ default:
+ break;
+ }
+
+ if (ret == TRANSITION_CHANGED) {
+ status->arming_state = new_arming_state;
+ arming_state_changed = true;
+ }
+ }
+
+ /* end of atomic state update */
+ irqrestore(flags);
+
+ if (ret == TRANSITION_DENIED)
+ warnx("arming transition rejected");
+
+ return ret;
+}
+
+bool is_safe(const struct vehicle_status_s *status, const struct safety_s *safety, const struct actuator_armed_s *armed)
+{
+ // System is safe if:
+ // 1) Not armed
+ // 2) Armed, but in software lockdown (HIL)
+ // 3) Safety switch is present AND engaged -> actuators locked
+ if (!armed->armed || (armed->armed && armed->lockdown) || (safety->safety_switch_available && !safety->safety_off)) {
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
+bool
+check_arming_state_changed()
+{
+ if (arming_state_changed) {
+ arming_state_changed = false;
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
+transition_result_t
+main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state)
+{
+ transition_result_t ret = TRANSITION_DENIED;
+
+ /* only check transition if the new state is actually different from the current one */
+ if (new_main_state == current_state->main_state) {
+ ret = TRANSITION_NOT_CHANGED;
+
+ } else {
+
+ switch (new_main_state) {
+ case MAIN_STATE_MANUAL:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_SEATBELT:
+
+ /* need at minimum altitude estimate */
+ if (current_state->condition_local_altitude_valid ||
+ current_state->condition_global_position_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+
+ break;
+
+ case MAIN_STATE_EASY:
+
+ /* need at minimum local position estimate */
+ if (current_state->condition_local_position_valid ||
+ current_state->condition_global_position_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+
+ break;
+
+ case MAIN_STATE_AUTO:
+
+ /* need global position estimate */
+ if (current_state->condition_global_position_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+
+ break;
+ }
+
+ if (ret == TRANSITION_CHANGED) {
+ current_state->main_state = new_main_state;
+ main_state_changed = true;
+ }
+ }
+
+ return ret;
+}
+
+bool
+check_main_state_changed()
+{
+ if (main_state_changed) {
+ main_state_changed = false;
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
+transition_result_t
+navigation_state_transition(struct vehicle_status_s *status, navigation_state_t new_navigation_state, struct vehicle_control_mode_s *control_mode)
+{
+ transition_result_t ret = TRANSITION_DENIED;
+
+ /* only check transition if the new state is actually different from the current one */
+ if (new_navigation_state == status->navigation_state) {
+ ret = TRANSITION_NOT_CHANGED;
+
+ } else {
+
+ switch (new_navigation_state) {
+ case NAVIGATION_STATE_DIRECT:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = false;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_altitude_enabled = false;
+ control_mode->flag_control_climb_rate_enabled = false;
+ control_mode->flag_control_manual_enabled = true;
+ control_mode->flag_control_auto_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_STABILIZE:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_altitude_enabled = false;
+ control_mode->flag_control_climb_rate_enabled = false;
+ control_mode->flag_control_manual_enabled = true;
+ control_mode->flag_control_auto_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_ALTHOLD:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = true;
+ control_mode->flag_control_auto_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_VECTOR:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = true;
+ control_mode->flag_control_auto_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_AUTO_READY:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = false;
+ control_mode->flag_control_attitude_enabled = false;
+ control_mode->flag_control_velocity_enabled = false;
+ control_mode->flag_control_position_enabled = false;
+ control_mode->flag_control_altitude_enabled = false;
+ control_mode->flag_control_climb_rate_enabled = false;
+ control_mode->flag_control_manual_enabled = false;
+ control_mode->flag_control_auto_enabled = true;
+ break;
+
+ case NAVIGATION_STATE_AUTO_TAKEOFF:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ control_mode->flag_control_auto_enabled = true;
+ break;
+
+ case NAVIGATION_STATE_AUTO_LOITER:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ control_mode->flag_control_auto_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_AUTO_MISSION:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ control_mode->flag_control_auto_enabled = true;
+ break;
+
+ case NAVIGATION_STATE_AUTO_RTL:
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ control_mode->flag_control_auto_enabled = true;
+ break;
+
+ case NAVIGATION_STATE_AUTO_LAND:
+
+ /* deny transitions from landed state */
+ if (status->navigation_state != NAVIGATION_STATE_AUTO_READY) {
+ ret = TRANSITION_CHANGED;
+ control_mode->flag_control_rates_enabled = true;
+ control_mode->flag_control_attitude_enabled = true;
+ control_mode->flag_control_velocity_enabled = true;
+ control_mode->flag_control_position_enabled = true;
+ control_mode->flag_control_altitude_enabled = true;
+ control_mode->flag_control_climb_rate_enabled = true;
+ control_mode->flag_control_manual_enabled = false;
+ control_mode->flag_control_auto_enabled = true;
+ }
+
+ break;
+
+ default:
+ break;
+ }
+
+ if (ret == TRANSITION_CHANGED) {
+ status->navigation_state = new_navigation_state;
+ control_mode->auto_state = status->navigation_state;
+ navigation_state_changed = true;
+ }
+ }
+
+ return ret;
+}
+
+bool
+check_navigation_state_changed()
+{
+ if (navigation_state_changed) {
+ navigation_state_changed = false;
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
+void
+set_navigation_state_changed()
+{
+ navigation_state_changed = true;
+}
+
+/**
+* Transition from one hil state to another
+*/
+int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, int control_mode_pub, struct vehicle_control_mode_s *current_control_mode, const int mavlink_fd)
+{
+ bool valid_transition = false;
+ int ret = ERROR;
+
+ warnx("Current state: %d, requested state: %d", current_status->hil_state, new_state);
+
+ if (current_status->hil_state == new_state) {
+ warnx("Hil state not changed");
+ valid_transition = true;
+
+ } else {
+
+ switch (new_state) {
+
+ case HIL_STATE_OFF:
+
+ /* we're in HIL and unexpected things can happen if we disable HIL now */
+ mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)");
+ valid_transition = false;
+
+ break;
+
+ case HIL_STATE_ON:
+
+ if (current_status->arming_state == ARMING_STATE_INIT
+ || current_status->arming_state == ARMING_STATE_STANDBY
+ || current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
+
+ current_control_mode->flag_system_hil_enabled = true;
+ mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
+ valid_transition = true;
+
+ // Disable publication of all attached sensors
+
+ /* list directory */
+ DIR *d;
+ struct dirent *direntry;
+ d = opendir("/dev");
+ if (d) {
+
+ while ((direntry = readdir(d)) != NULL) {
+
+ int sensfd = ::open(direntry->d_name, 0);
+ int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 0);
+ close(sensfd);
+
+ printf("Disabling %s\n: %s", direntry->d_name, (!block_ret) ? "OK" : "FAIL");
+ }
+
+ closedir(d);
+
+ warnx("directory listing ok (FS mounted and readable)");
+
+ } else {
+ /* failed opening dir */
+ warnx("FAILED LISTING DEVICE ROOT DIRECTORY");
+ return 1;
+ }
+ }
+
+ break;
+
+ default:
+ warnx("Unknown hil state");
+ break;
+ }
+ }
+
+ if (valid_transition) {
+ current_status->hil_state = new_state;
+
+ current_status->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+
+ current_control_mode->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, current_control_mode);
+
+ // XXX also set lockdown here
+
+ ret = OK;
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition");
+ }
+
+ return ret;
+}
+
+
+
+// /*
+// * Wrapper functions (to be used in the commander), all functions assume lock on current_status
+// */
+
+// /* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR
+// *
+// * START SUBSYSTEM/EMERGENCY FUNCTIONS
+// * */
+
+// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
+// {
+// current_status->onboard_control_sensors_present |= 1 << *subsystem_type;
+// current_status->counter++;
+// current_status->timestamp = hrt_absolute_time();
+// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+// }
+
+// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
+// {
+// current_status->onboard_control_sensors_present &= ~(1 << *subsystem_type);
+// current_status->counter++;
+// current_status->timestamp = hrt_absolute_time();
+// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+
+// /* if a subsystem was removed something went completely wrong */
+
+// switch (*subsystem_type) {
+// case SUBSYSTEM_TYPE_GYRO:
+// //global_data_send_mavlink_statustext_message_out("Commander: gyro not present", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency_always_critical(status_pub, current_status);
+// break;
+
+// case SUBSYSTEM_TYPE_ACC:
+// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer not present", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency_always_critical(status_pub, current_status);
+// break;
+
+// case SUBSYSTEM_TYPE_MAG:
+// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer not present", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency_always_critical(status_pub, current_status);
+// break;
+
+// case SUBSYSTEM_TYPE_GPS:
+// {
+// uint8_t flight_env = global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV];
+
+// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
+// //global_data_send_mavlink_statustext_message_out("Commander: GPS not present", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency(status_pub, current_status);
+// }
+// }
+// break;
+
+// default:
+// break;
+// }
+
+// }
+
+// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
+// {
+// current_status->onboard_control_sensors_enabled |= 1 << *subsystem_type;
+// current_status->counter++;
+// current_status->timestamp = hrt_absolute_time();
+// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+// }
+
+// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
+// {
+// current_status->onboard_control_sensors_enabled &= ~(1 << *subsystem_type);
+// current_status->counter++;
+// current_status->timestamp = hrt_absolute_time();
+// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+
+// /* if a subsystem was disabled something went completely wrong */
+
+// switch (*subsystem_type) {
+// case SUBSYSTEM_TYPE_GYRO:
+// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - gyro disabled", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency_always_critical(status_pub, current_status);
+// break;
+
+// case SUBSYSTEM_TYPE_ACC:
+// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - accelerometer disabled", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency_always_critical(status_pub, current_status);
+// break;
+
+// case SUBSYSTEM_TYPE_MAG:
+// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - magnetometer disabled", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency_always_critical(status_pub, current_status);
+// break;
+
+// case SUBSYSTEM_TYPE_GPS:
+// {
+// uint8_t flight_env = (uint8_t)(global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV]);
+
+// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
+// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - GPS disabled", MAV_SEVERITY_EMERGENCY);
+// state_machine_emergency(status_pub, current_status);
+// }
+// }
+// break;
+
+// default:
+// break;
+// }
+
+// }
+
+
+///* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
+//
+//int update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
+//{
+// int ret = 1;
+//
+//// /* Switch on HIL if in standby and not already in HIL mode */
+//// if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED)
+//// && !current_status->flag_hil_enabled) {
+//// if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) {
+//// /* Enable HIL on request */
+//// current_status->flag_hil_enabled = true;
+//// ret = OK;
+//// state_machine_publish(status_pub, current_status, mavlink_fd);
+//// publish_armed_status(current_status);
+//// printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n");
+////
+//// } else if (current_status->state_machine != SYSTEM_STATE_STANDBY &&
+//// current_status->flag_fmu_armed) {
+////
+//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, disarm first!")
+////
+//// } else {
+////
+//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, not in standby.")
+//// }
+//// }
+//
+// /* switch manual / auto */
+// if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) {
+// update_state_machine_mode_auto(status_pub, current_status, mavlink_fd);
+//
+// } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) {
+// update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd);
+//
+// } else if (mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED) {
+// update_state_machine_mode_guided(status_pub, current_status, mavlink_fd);
+//
+// } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) {
+// update_state_machine_mode_manual(status_pub, current_status, mavlink_fd);
+// }
+//
+// /* vehicle is disarmed, mode requests arming */
+// if (!(current_status->flag_fmu_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
+// /* only arm in standby state */
+// // XXX REMOVE
+// if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
+// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
+// ret = OK;
+// printf("[cmd] arming due to command request\n");
+// }
+// }
+//
+// /* vehicle is armed, mode requests disarming */
+// if (current_status->flag_fmu_armed && !(mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
+// /* only disarm in ground ready */
+// if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
+// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
+// ret = OK;
+// printf("[cmd] disarming due to command request\n");
+// }
+// }
+//
+// /* NEVER actually switch off HIL without reboot */
+// if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) {
+// warnx("DENYING request to switch off HIL. Please power cycle (safety reasons)\n");
+// mavlink_log_critical(mavlink_fd, "Power-cycle to exit HIL");
+// ret = ERROR;
+// }
+//
+// return ret;
+//}
+
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 2f2ccc729..0bfdf36a8 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
*
@@ -46,164 +46,34 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
-/**
- * Switch to new state with no checking.
- *
- * do_state_update: this is the functions that all other functions have to call in order to update the state.
- * the function does not question the state change, this must be done before
- * The function performs actions that are connected with the new state (buzzer, reboot, ...)
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- *
- * @return 0 (macro OK) or 1 on error (macro ERROR)
- */
-int do_state_update(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, commander_state_machine_t new_state);
+typedef enum {
+ TRANSITION_DENIED = -1,
+ TRANSITION_NOT_CHANGED = 0,
+ TRANSITION_CHANGED
-/* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR */
-// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
+} transition_result_t;
-// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
+transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
+ const struct vehicle_control_mode_s *control_mode, arming_state_t new_arming_state, struct actuator_armed_s *armed);
-// void update_state_machine_subsystem_healthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
+bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
+bool check_arming_state_changed();
-/**
- * Handle state machine if got position fix
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
+transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state);
-/**
- * Handle state machine if position fix lost
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
+bool check_main_state_changed();
-/**
- * Handle state machine if user wants to arm
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
+transition_result_t navigation_state_transition(struct vehicle_status_s *status, navigation_state_t new_navigation_state, struct vehicle_control_mode_s *control_mode);
-/**
- * Handle state machine if user wants to disarm
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is manual
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is stabilized
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is guided
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_guided(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is auto
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Publish current state information
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_publish(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-
-/*
- * Functions that handle incoming requests to change the state machine or a parameter (probably from the mavlink app).
- * If the request is obeyed the functions return 0
- *
- */
-
-/**
- * Handles *incoming request* to switch to a specific state, if state change is successful returns 0
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode);
-
-/**
- * Handles *incoming request* to switch to a specific custom state, if state change is successful returns 0
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t custom_mode);
-
-/**
- * Always switches to critical mode under any circumstances.
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Switches to emergency if required.
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_emergency(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Publish the armed state depending on the current system state
- *
- * @param current_status the current system status
- */
-void publish_armed_status(const struct vehicle_status_s *current_status);
+bool check_navigation_state_changed();
+void set_navigation_state_changed();
+int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, int control_mode_pub, struct vehicle_control_mode_s *current_control_mode, const int mavlink_fd);
#endif /* STATE_MACHINE_HELPER_H_ */
diff --git a/src/modules/controllib/block/Block.cpp b/src/modules/controllib/block/Block.cpp
index 5994d2315..b964d40a3 100644
--- a/src/modules/controllib/block/Block.cpp
+++ b/src/modules/controllib/block/Block.cpp
@@ -43,8 +43,8 @@
#include "Block.hpp"
#include "BlockParam.hpp"
-#include "UOrbSubscription.hpp"
-#include "UOrbPublication.hpp"
+#include "../uorb/UOrbSubscription.hpp"
+#include "../uorb/UOrbPublication.hpp"
namespace control
{
diff --git a/src/modules/controllib/block/BlockParam.hpp b/src/modules/controllib/block/BlockParam.hpp
index 58a9bfc0d..36bc8c24b 100644
--- a/src/modules/controllib/block/BlockParam.hpp
+++ b/src/modules/controllib/block/BlockParam.hpp
@@ -69,22 +69,39 @@ protected:
/**
* Parameters that are tied to blocks for updating and nameing.
*/
-template<class T>
-class __EXPORT BlockParam : public BlockParamBase
+
+class __EXPORT BlockParamFloat : public BlockParamBase
+{
+public:
+ BlockParamFloat(Block *block, const char *name, bool parent_prefix=true) :
+ BlockParamBase(block, name, parent_prefix),
+ _val() {
+ update();
+ }
+ float get() { return _val; }
+ void set(float val) { _val = val; }
+ void update() {
+ if (_handle != PARAM_INVALID) param_get(_handle, &_val);
+ }
+protected:
+ float _val;
+};
+
+class __EXPORT BlockParamInt : public BlockParamBase
{
public:
- BlockParam(Block *block, const char *name, bool parent_prefix=true) :
+ BlockParamInt(Block *block, const char *name, bool parent_prefix=true) :
BlockParamBase(block, name, parent_prefix),
_val() {
update();
}
- T get() { return _val; }
- void set(T val) { _val = val; }
+ int get() { return _val; }
+ void set(int val) { _val = val; }
void update() {
if (_handle != PARAM_INVALID) param_get(_handle, &_val);
}
protected:
- T _val;
+ int _val;
};
} // namespace control
diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp
index 7a785d12e..66e929038 100644
--- a/src/modules/controllib/blocks.hpp
+++ b/src/modules/controllib/blocks.hpp
@@ -42,6 +42,7 @@
#include <assert.h>
#include <time.h>
#include <stdlib.h>
+#include <math.h>
#include <mathlib/math/test/test.hpp>
#include "block/Block.hpp"
@@ -73,8 +74,8 @@ public:
float getMax() { return _max.get(); }
protected:
// attributes
- BlockParam<float> _min;
- BlockParam<float> _max;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
};
int __EXPORT blockLimitTest();
@@ -98,7 +99,7 @@ public:
float getMax() { return _max.get(); }
protected:
// attributes
- BlockParam<float> _max;
+ control::BlockParamFloat _max;
};
int __EXPORT blockLimitSymTest();
@@ -125,7 +126,7 @@ public:
protected:
// attributes
float _state;
- BlockParam<float> _fCut;
+ control::BlockParamFloat _fCut;
};
int __EXPORT blockLowPassTest();
@@ -156,7 +157,7 @@ protected:
// attributes
float _u; /**< previous input */
float _y; /**< previous output */
- BlockParam<float> _fCut; /**< cut-off frequency, Hz */
+ control::BlockParamFloat _fCut; /**< cut-off frequency, Hz */
};
int __EXPORT blockHighPassTest();
@@ -272,7 +273,7 @@ public:
// accessors
float getKP() { return _kP.get(); }
protected:
- BlockParam<float> _kP;
+ control::BlockParamFloat _kP;
};
int __EXPORT blockPTest();
@@ -302,8 +303,8 @@ public:
BlockIntegral &getIntegral() { return _integral; }
private:
BlockIntegral _integral;
- BlockParam<float> _kP;
- BlockParam<float> _kI;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kI;
};
int __EXPORT blockPITest();
@@ -333,8 +334,8 @@ public:
BlockDerivative &getDerivative() { return _derivative; }
private:
BlockDerivative _derivative;
- BlockParam<float> _kP;
- BlockParam<float> _kD;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kD;
};
int __EXPORT blockPDTest();
@@ -371,9 +372,9 @@ private:
// attributes
BlockIntegral _integral;
BlockDerivative _derivative;
- BlockParam<float> _kP;
- BlockParam<float> _kI;
- BlockParam<float> _kD;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kI;
+ control::BlockParamFloat _kD;
};
int __EXPORT blockPIDTest();
@@ -403,7 +404,7 @@ public:
float get() { return _val; }
private:
// attributes
- BlockParam<float> _trim;
+ control::BlockParamFloat _trim;
BlockLimit _limit;
float _val;
};
@@ -438,8 +439,8 @@ public:
float getMax() { return _max.get(); }
private:
// attributes
- BlockParam<float> _min;
- BlockParam<float> _max;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
};
int __EXPORT blockRandUniformTest();
@@ -485,8 +486,8 @@ public:
float getStdDev() { return _stdDev.get(); }
private:
// attributes
- BlockParam<float> _mean;
- BlockParam<float> _stdDev;
+ control::BlockParamFloat _mean;
+ control::BlockParamFloat _stdDev;
};
int __EXPORT blockRandGaussTest();
diff --git a/src/modules/controllib/module.mk b/src/modules/controllib/module.mk
index 13d1069c7..d815a8feb 100644
--- a/src/modules/controllib/module.mk
+++ b/src/modules/controllib/module.mk
@@ -37,7 +37,7 @@
SRCS = test_params.c \
block/Block.cpp \
block/BlockParam.cpp \
- block/UOrbPublication.cpp \
- block/UOrbSubscription.cpp \
- blocks.cpp \
- fixedwing.cpp
+ uorb/UOrbPublication.cpp \
+ uorb/UOrbSubscription.cpp \
+ uorb/blocks.cpp \
+ blocks.cpp
diff --git a/src/modules/controllib/block/UOrbPublication.cpp b/src/modules/controllib/uorb/UOrbPublication.cpp
index f69b39d90..f69b39d90 100644
--- a/src/modules/controllib/block/UOrbPublication.cpp
+++ b/src/modules/controllib/uorb/UOrbPublication.cpp
diff --git a/src/modules/controllib/block/UOrbPublication.hpp b/src/modules/controllib/uorb/UOrbPublication.hpp
index a36f4429f..6f1f3fc1c 100644
--- a/src/modules/controllib/block/UOrbPublication.hpp
+++ b/src/modules/controllib/uorb/UOrbPublication.hpp
@@ -39,8 +39,8 @@
#pragma once
#include <uORB/uORB.h>
-#include "Block.hpp"
-#include "List.hpp"
+#include "../block/Block.hpp"
+#include "../block/List.hpp"
namespace control
@@ -60,11 +60,15 @@ public:
List<UOrbPublicationBase *> * list,
const struct orb_metadata *meta) :
_meta(meta),
- _handle() {
+ _handle(-1) {
if (list != NULL) list->add(this);
}
void update() {
- orb_publish(getMeta(), getHandle(), getDataVoidPtr());
+ if (_handle > 0) {
+ orb_publish(getMeta(), getHandle(), getDataVoidPtr());
+ } else {
+ setHandle(orb_advertise(getMeta(), getDataVoidPtr()));
+ }
}
virtual void *getDataVoidPtr() = 0;
virtual ~UOrbPublicationBase() {
@@ -99,10 +103,6 @@ public:
const struct orb_metadata *meta) :
T(), // initialize data structure to zero
UOrbPublicationBase(list, meta) {
- // It is important that we call T()
- // before we publish the data, so we
- // call this here instead of the base class
- setHandle(orb_advertise(getMeta(), getDataVoidPtr()));
}
virtual ~UOrbPublication() {}
/*
diff --git a/src/modules/controllib/block/UOrbSubscription.cpp b/src/modules/controllib/uorb/UOrbSubscription.cpp
index 022cadd24..022cadd24 100644
--- a/src/modules/controllib/block/UOrbSubscription.cpp
+++ b/src/modules/controllib/uorb/UOrbSubscription.cpp
diff --git a/src/modules/controllib/block/UOrbSubscription.hpp b/src/modules/controllib/uorb/UOrbSubscription.hpp
index 22cc2e114..d337d89a8 100644
--- a/src/modules/controllib/block/UOrbSubscription.hpp
+++ b/src/modules/controllib/uorb/UOrbSubscription.hpp
@@ -39,8 +39,8 @@
#pragma once
#include <uORB/uORB.h>
-#include "Block.hpp"
-#include "List.hpp"
+#include "../block/Block.hpp"
+#include "../block/List.hpp"
namespace control
diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp
new file mode 100644
index 000000000..448a42a99
--- /dev/null
+++ b/src/modules/controllib/uorb/blocks.cpp
@@ -0,0 +1,101 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 uorb_blocks.cpp
+ *
+ * uorb block library code
+ */
+
+#include "blocks.hpp"
+
+namespace control
+{
+
+BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
+ SuperBlock(parent, name),
+ _xtYawLimit(this, "XT2YAW"),
+ _xt2Yaw(this, "XT2YAW"),
+ _psiCmd(0)
+{
+}
+
+BlockWaypointGuidance::~BlockWaypointGuidance() {};
+
+void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
+ vehicle_attitude_s &att,
+ vehicle_global_position_setpoint_s &posCmd,
+ vehicle_global_position_setpoint_s &lastPosCmd)
+{
+
+ // heading to waypoint
+ float psiTrack = get_bearing_to_next_waypoint(
+ (double)pos.lat / (double)1e7d,
+ (double)pos.lon / (double)1e7d,
+ (double)posCmd.lat / (double)1e7d,
+ (double)posCmd.lon / (double)1e7d);
+
+ // cross track
+ struct crosstrack_error_s xtrackError;
+ get_distance_to_line(&xtrackError,
+ (double)pos.lat / (double)1e7d,
+ (double)pos.lon / (double)1e7d,
+ (double)lastPosCmd.lat / (double)1e7d,
+ (double)lastPosCmd.lon / (double)1e7d,
+ (double)posCmd.lat / (double)1e7d,
+ (double)posCmd.lon / (double)1e7d);
+
+ _psiCmd = _wrap_2pi(psiTrack -
+ _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
+}
+
+BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
+ SuperBlock(parent, name),
+ // subscriptions
+ _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
+ _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
+ _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
+ _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
+ _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
+ _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
+ _status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
+ _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
+ // publications
+ _actuators(&getPublications(), ORB_ID(actuator_controls_0))
+{
+}
+
+BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {};
+
+} // namespace control
+
diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp
new file mode 100644
index 000000000..46dc1bec2
--- /dev/null
+++ b/src/modules/controllib/uorb/blocks.hpp
@@ -0,0 +1,113 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 uorb_blocks.h
+ *
+ * uorb block library code
+ */
+
+#pragma once
+
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/parameter_update.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <math.h>
+
+#include <drivers/drv_hrt.h>
+#include <poll.h>
+
+extern "C" {
+#include <geo/geo.h>
+}
+
+#include "../blocks.hpp"
+#include "UOrbSubscription.hpp"
+#include "UOrbPublication.hpp"
+
+namespace control
+{
+
+/**
+ * Waypoint Guidance block
+ */
+class __EXPORT BlockWaypointGuidance : public SuperBlock
+{
+private:
+ BlockLimitSym _xtYawLimit;
+ BlockP _xt2Yaw;
+ float _psiCmd;
+public:
+ BlockWaypointGuidance(SuperBlock *parent, const char *name);
+ virtual ~BlockWaypointGuidance();
+ void update(vehicle_global_position_s &pos,
+ vehicle_attitude_s &att,
+ vehicle_global_position_setpoint_s &posCmd,
+ vehicle_global_position_setpoint_s &lastPosCmd);
+ float getPsiCmd() { return _psiCmd; }
+};
+
+/**
+ * UorbEnabledAutopilot
+ */
+class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
+{
+protected:
+ // subscriptions
+ UOrbSubscription<vehicle_attitude_s> _att;
+ UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
+ UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
+ UOrbSubscription<vehicle_global_position_s> _pos;
+ UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
+ UOrbSubscription<manual_control_setpoint_s> _manual;
+ UOrbSubscription<vehicle_status_s> _status;
+ UOrbSubscription<parameter_update_s> _param_update;
+ // publications
+ UOrbPublication<actuator_controls_s> _actuators;
+public:
+ BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
+ virtual ~BlockUorbEnabledAutopilot();
+};
+
+} // namespace control
+
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
index 769b8b0a8..2aeca3a98 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
@@ -128,8 +128,8 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
if (!initialized) {
parameters_init(&h);
parameters_update(&h, &p);
- pid_init(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim, PID_MODE_DERIVATIV_NONE); //P Controller
- pid_init(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim, PID_MODE_DERIVATIV_NONE); //P Controller
+ pid_init(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim, PID_MODE_DERIVATIV_NONE, 0.0f); //P Controller
+ pid_init(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim, PID_MODE_DERIVATIV_NONE, 0.0f); //P Controller
initialized = true;
}
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
index 6c9c137bb..b6b4546c2 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
@@ -53,6 +53,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
@@ -116,6 +117,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
memset(&global_pos, 0, sizeof(global_pos));
struct manual_control_setpoint_s manual_sp;
memset(&manual_sp, 0, sizeof(manual_sp));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
struct vehicle_status_s vstatus;
memset(&vstatus, 0, sizeof(vstatus));
@@ -137,7 +140,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
/* Setup of loop */
float gyro[3] = {0.0f, 0.0f, 0.0f};
@@ -178,30 +182,16 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
}
orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus);
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
+ orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
gyro[0] = att.rollspeed;
gyro[1] = att.pitchspeed;
gyro[2] = att.yawspeed;
- /* control */
-
- if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
- vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
- /* attitude control */
- fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
-
- /* angular rate control */
- fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
-
- /* pass through throttle */
- actuators.control[3] = att_sp.thrust;
-
- /* set flaps to zero */
- actuators.control[4] = 0.0f;
-
- } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
- if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
+ /* set manual setpoints if required */
+ if (control_mode.flag_control_manual_enabled) {
+ if (control_mode.flag_control_attitude_enabled) {
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
if (vstatus.rc_signal_lost) {
@@ -234,15 +224,6 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
att_sp.timestamp = hrt_absolute_time();
- /* attitude control */
- fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
-
- /* angular rate control */
- fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
-
- /* pass through throttle */
- actuators.control[3] = att_sp.thrust;
-
/* pass through flaps */
if (isfinite(manual_sp.flaps)) {
actuators.control[4] = manual_sp.flaps;
@@ -251,7 +232,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
actuators.control[4] = 0.0f;
}
- } else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+ } else {
/* directly pass through values */
actuators.control[0] = manual_sp.roll;
/* positive pitch means negative actuator -> pull up */
@@ -267,6 +248,22 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
}
}
}
+
+ /* execute attitude control if requested */
+ if (control_mode.flag_control_attitude_enabled) {
+ /* attitude control */
+ fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
+
+ /* angular rate control */
+ fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
+
+ /* pass through throttle */
+ actuators.control[3] = att_sp.thrust;
+
+ /* set flaps to zero */
+ actuators.control[4] = 0.0f;
+
+ }
/* publish rates */
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
index 4eccc118c..cdab39edc 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -179,9 +179,9 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
if (!initialized) {
parameters_init(&h);
parameters_update(&h, &p);
- pid_init(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the controller layout is with a PI rate controller
- pid_init(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
- pid_init(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1, PID_MODE_DERIVATIV_NONE); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
+ pid_init(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1, PID_MODE_DERIVATIV_NONE, 0.0f); // set D part to 0 because the controller layout is with a PI rate controller
+ pid_init(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1, PID_MODE_DERIVATIV_NONE, 0.0f); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
+ pid_init(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1, PID_MODE_DERIVATIV_NONE, 0.0f); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
initialized = true;
}
diff --git a/src/modules/controllib/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index 7be38015c..6dc19df41 100644
--- a/src/modules/controllib/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -86,61 +86,6 @@ void BlockStabilization::update(float pCmd, float qCmd, float rCmd,
_yawDamper.update(rCmd, r, outputScale);
}
-BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
- SuperBlock(parent, name),
- _xtYawLimit(this, "XT2YAW"),
- _xt2Yaw(this, "XT2YAW"),
- _psiCmd(0)
-{
-}
-
-BlockWaypointGuidance::~BlockWaypointGuidance() {};
-
-void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
- vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd)
-{
-
- // heading to waypoint
- float psiTrack = get_bearing_to_next_waypoint(
- (double)pos.lat / (double)1e7d,
- (double)pos.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
-
- // cross track
- struct crosstrack_error_s xtrackError;
- get_distance_to_line(&xtrackError,
- (double)pos.lat / (double)1e7d,
- (double)pos.lon / (double)1e7d,
- (double)lastPosCmd.lat / (double)1e7d,
- (double)lastPosCmd.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
-
- _psiCmd = _wrap_2pi(psiTrack -
- _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
-}
-
-BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
- SuperBlock(parent, name),
- // subscriptions
- _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
- _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
- _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
- _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
- _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_setpoint), 20),
- _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
- _status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
- _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
- // publications
- _actuators(&getPublications(), ORB_ID(actuator_controls_0))
-{
-}
-
-BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {};
-
BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) :
BlockUorbEnabledAutopilot(parent, name),
_stabilization(this, ""), // no name needed, already unique
@@ -211,9 +156,10 @@ void BlockMultiModeBacksideAutopilot::update()
_actuators.control[i] = 0.0f;
// only update guidance in auto mode
- if (_status.state_machine == SYSTEM_STATE_AUTO) {
+ if (_status.main_state == MAIN_STATE_AUTO) {
+ // TODO use vehicle_control_mode here?
// update guidance
- _guide.update(_pos, _att, _posCmd, _lastPosCmd);
+ _guide.update(_pos, _att, _posCmd.current, _lastPosCmd.current);
}
// XXX handle STABILIZED (loiter on spot) as well
@@ -221,14 +167,11 @@ void BlockMultiModeBacksideAutopilot::update()
// the setpoint should update to loitering around this position
// handle autopilot modes
- if (_status.state_machine == SYSTEM_STATE_AUTO ||
- _status.state_machine == SYSTEM_STATE_STABILIZED) {
+ if (_status.main_state == MAIN_STATE_AUTO) {
- // update guidance
- _guide.update(_pos, _att, _posCmd, _lastPosCmd);
-
- // calculate velocity, XXX should be airspeed, but using ground speed for now
- // for the purpose of control we will limit the velocity feedback between
+ // calculate velocity, XXX should be airspeed,
+ // but using ground speed for now for the purpose
+ // of control we will limit the velocity feedback between
// the min/max velocity
float v = _vLimit.update(sqrtf(
_pos.vx * _pos.vx +
@@ -239,7 +182,7 @@ void BlockMultiModeBacksideAutopilot::update()
float vCmd = _vLimit.update(_vCmd.get());
// altitude hold
- float dThrottle = _h2Thr.update(_posCmd.altitude - _pos.alt);
+ float dThrottle = _h2Thr.update(_posCmd.current.altitude - _pos.alt);
// heading hold
float psiError = _wrap_pi(_guide.getPsiCmd() - _att.yaw);
@@ -273,90 +216,87 @@ void BlockMultiModeBacksideAutopilot::update()
// a first binary release can be targeted.
// This is not a hack, but a design choice.
- /* do not limit in HIL */
- if (!_status.flag_hil_enabled) {
+ // do not limit in HIL
+ if (_status.hil_state != HIL_STATE_ON) {
/* limit to value of manual throttle */
_actuators.control[CH_THR] = (_actuators.control[CH_THR] < _manual.throttle) ?
_actuators.control[CH_THR] : _manual.throttle;
}
- } else if (_status.state_machine == SYSTEM_STATE_MANUAL) {
-
- if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
- _actuators.control[CH_AIL] = _manual.roll;
- _actuators.control[CH_ELV] = _manual.pitch;
- _actuators.control[CH_RDR] = _manual.yaw;
- _actuators.control[CH_THR] = _manual.throttle;
-
- } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
-
- // calculate velocity, XXX should be airspeed, but using ground speed for now
- // for the purpose of control we will limit the velocity feedback between
- // the min/max velocity
- float v = _vLimit.update(sqrtf(
- _pos.vx * _pos.vx +
- _pos.vy * _pos.vy +
- _pos.vz * _pos.vz));
-
- // pitch channel -> rate of climb
- // TODO, might want to put a gain on this, otherwise commanding
- // from +1 -> -1 m/s for rate of climb
- //float dThrottle = _cr2Thr.update(
- //_crMax.get()*_manual.pitch - _pos.vz);
-
- // roll channel -> bank angle
- float phiCmd = _phiLimit.update(_manual.roll * _phiLimit.getMax());
- float pCmd = _phi2P.update(phiCmd - _att.roll);
-
- // throttle channel -> velocity
- // negative sign because nose over to increase speed
- float vCmd = _vLimit.update(_manual.throttle *
- (_vLimit.getMax() - _vLimit.getMin()) +
- _vLimit.getMin());
- float thetaCmd = _theLimit.update(-_v2Theta.update(vCmd - v));
- float qCmd = _theta2Q.update(thetaCmd - _att.pitch);
-
- // yaw rate cmd
- float rCmd = 0;
-
- // stabilization
- _stabilization.update(pCmd, qCmd, rCmd,
- _att.rollspeed, _att.pitchspeed, _att.yawspeed);
-
- // output
- _actuators.control[CH_AIL] = _stabilization.getAileron() + _trimAil.get();
- _actuators.control[CH_ELV] = _stabilization.getElevator() + _trimElv.get();
- _actuators.control[CH_RDR] = _stabilization.getRudder() + _trimRdr.get();
-
- // currenlty using manual throttle
- // XXX if you enable this watch out, vz might be very noisy
- //_actuators.control[CH_THR] = dThrottle + _trimThr.get();
- _actuators.control[CH_THR] = _manual.throttle;
-
- // XXX limit throttle to manual setting (safety) for now.
- // If it turns out to be confusing, it can be removed later once
- // a first binary release can be targeted.
- // This is not a hack, but a design choice.
-
- /* do not limit in HIL */
- if (!_status.flag_hil_enabled) {
- /* limit to value of manual throttle */
- _actuators.control[CH_THR] = (_actuators.control[CH_THR] < _manual.throttle) ?
- _actuators.control[CH_THR] : _manual.throttle;
- }
- }
+ } else if (_status.main_state == MAIN_STATE_MANUAL) {
+ _actuators.control[CH_AIL] = _manual.roll;
+ _actuators.control[CH_ELV] = _manual.pitch;
+ _actuators.control[CH_RDR] = _manual.yaw;
+ _actuators.control[CH_THR] = _manual.throttle;
+
+ } else if (_status.main_state == MAIN_STATE_SEATBELT ||
+ _status.main_state == MAIN_STATE_EASY /* TODO, implement easy */) {
+
+ // calculate velocity, XXX should be airspeed, but using ground speed for now
+ // for the purpose of control we will limit the velocity feedback between
+ // the min/max velocity
+ float v = _vLimit.update(sqrtf(
+ _pos.vx * _pos.vx +
+ _pos.vy * _pos.vy +
+ _pos.vz * _pos.vz));
+
+ // pitch channel -> rate of climb
+ // TODO, might want to put a gain on this, otherwise commanding
+ // from +1 -> -1 m/s for rate of climb
+ //float dThrottle = _cr2Thr.update(
+ //_crMax.get()*_manual.pitch - _pos.vz);
+
+ // roll channel -> bank angle
+ float phiCmd = _phiLimit.update(_manual.roll * _phiLimit.getMax());
+ float pCmd = _phi2P.update(phiCmd - _att.roll);
+
+ // throttle channel -> velocity
+ // negative sign because nose over to increase speed
+ float vCmd = _vLimit.update(_manual.throttle *
+ (_vLimit.getMax() - _vLimit.getMin()) +
+ _vLimit.getMin());
+ float thetaCmd = _theLimit.update(-_v2Theta.update(vCmd - v));
+ float qCmd = _theta2Q.update(thetaCmd - _att.pitch);
+
+ // yaw rate cmd
+ float rCmd = 0;
+
+ // stabilization
+ _stabilization.update(pCmd, qCmd, rCmd,
+ _att.rollspeed, _att.pitchspeed, _att.yawspeed);
- // body rates controller, disabled for now
- else if (0 /*_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS*/) {
+ // output
+ _actuators.control[CH_AIL] = _stabilization.getAileron() + _trimAil.get();
+ _actuators.control[CH_ELV] = _stabilization.getElevator() + _trimElv.get();
+ _actuators.control[CH_RDR] = _stabilization.getRudder() + _trimRdr.get();
- _stabilization.update(_manual.roll, _manual.pitch, _manual.yaw,
- _att.rollspeed, _att.pitchspeed, _att.yawspeed);
+ // currently using manual throttle
+ // XXX if you enable this watch out, vz might be very noisy
+ //_actuators.control[CH_THR] = dThrottle + _trimThr.get();
+ _actuators.control[CH_THR] = _manual.throttle;
+
+ // XXX limit throttle to manual setting (safety) for now.
+ // If it turns out to be confusing, it can be removed later once
+ // a first binary release can be targeted.
+ // This is not a hack, but a design choice.
- _actuators.control[CH_AIL] = _stabilization.getAileron();
- _actuators.control[CH_ELV] = _stabilization.getElevator();
- _actuators.control[CH_RDR] = _stabilization.getRudder();
- _actuators.control[CH_THR] = _manual.throttle;
+ /* do not limit in HIL */
+ if (_status.hil_state != HIL_STATE_ON) {
+ /* limit to value of manual throttle */
+ _actuators.control[CH_THR] = (_actuators.control[CH_THR] < _manual.throttle) ?
+ _actuators.control[CH_THR] : _manual.throttle;
}
+ // body rates controller, disabled for now
+ // TODO
+ } else if (0 /*_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS*/) { // TODO use vehicle_control_mode here?
+
+ _stabilization.update(_manual.roll, _manual.pitch, _manual.yaw,
+ _att.rollspeed, _att.pitchspeed, _att.yawspeed);
+
+ _actuators.control[CH_AIL] = _stabilization.getAileron();
+ _actuators.control[CH_ELV] = _stabilization.getElevator();
+ _actuators.control[CH_RDR] = _stabilization.getRudder();
+ _actuators.control[CH_THR] = _manual.throttle;
}
// update all publications
diff --git a/src/modules/controllib/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp
index 53d0cf893..567efeb35 100644
--- a/src/modules/controllib/fixedwing.hpp
+++ b/src/modules/fixedwing_backside/fixedwing.hpp
@@ -39,31 +39,8 @@
#pragma once
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/parameter_update.h>
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <math.h>
-
-#include <drivers/drv_hrt.h>
-#include <poll.h>
-
-#include "blocks.hpp"
-#include "block/UOrbSubscription.hpp"
-#include "block/UOrbPublication.hpp"
-
-extern "C" {
-#include <systemlib/geo/geo.h>
-}
+#include <controllib/blocks.hpp>
+#include <controllib/uorb/blocks.hpp>
namespace control
{
@@ -251,47 +228,6 @@ public:
*/
/**
- * Waypoint Guidance block
- */
-class __EXPORT BlockWaypointGuidance : public SuperBlock
-{
-private:
- BlockLimitSym _xtYawLimit;
- BlockP _xt2Yaw;
- float _psiCmd;
-public:
- BlockWaypointGuidance(SuperBlock *parent, const char *name);
- virtual ~BlockWaypointGuidance();
- void update(vehicle_global_position_s &pos,
- vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd);
- float getPsiCmd() { return _psiCmd; }
-};
-
-/**
- * UorbEnabledAutopilot
- */
-class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
-{
-protected:
- // subscriptions
- UOrbSubscription<vehicle_attitude_s> _att;
- UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
- UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
- UOrbSubscription<vehicle_global_position_s> _pos;
- UOrbSubscription<vehicle_global_position_setpoint_s> _posCmd;
- UOrbSubscription<manual_control_setpoint_s> _manual;
- UOrbSubscription<vehicle_status_s> _status;
- UOrbSubscription<parameter_update_s> _param_update;
- // publications
- UOrbPublication<actuator_controls_s> _actuators;
-public:
- BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
- virtual ~BlockUorbEnabledAutopilot();
-};
-
-/**
* Multi-mode Autopilot
*/
class __EXPORT BlockMultiModeBacksideAutopilot : public BlockUorbEnabledAutopilot
@@ -319,16 +255,16 @@ private:
BlockWaypointGuidance _guide;
// block params
- BlockParam<float> _trimAil;
- BlockParam<float> _trimElv;
- BlockParam<float> _trimRdr;
- BlockParam<float> _trimThr;
- BlockParam<float> _trimV;
- BlockParam<float> _vCmd;
- BlockParam<float> _crMax;
+ BlockParamFloat _trimAil;
+ BlockParamFloat _trimElv;
+ BlockParamFloat _trimRdr;
+ BlockParamFloat _trimThr;
+ BlockParamFloat _trimV;
+ BlockParamFloat _vCmd;
+ BlockParamFloat _crMax;
struct pollfd _attPoll;
- vehicle_global_position_setpoint_s _lastPosCmd;
+ vehicle_global_position_set_triplet_s _lastPosCmd;
enum {CH_AIL, CH_ELV, CH_RDR, CH_THR};
uint64_t _timeStamp;
public:
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index e2330427d..f4ea05088 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -45,11 +45,13 @@
#include <stdlib.h>
#include <string.h>
#include <systemlib/systemlib.h>
-#include <controllib/fixedwing.hpp>
#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
+#include "fixedwing.hpp"
+
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
@@ -80,7 +82,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: control_demo {start|stop|status} [-p <additional params>]\n\n");
+ fprintf(stderr, "usage: fixedwing_backside {start|stop|status} [-p <additional params>]\n\n");
exit(1);
}
@@ -101,13 +103,14 @@ int fixedwing_backside_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("control_demo already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn_cmd("control_demo",
+
+ deamon_task = task_spawn_cmd("fixedwing_backside",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
@@ -128,10 +131,10 @@ int fixedwing_backside_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tcontrol_demo app is running\n");
+ warnx("is running");
} else {
- printf("\tcontrol_demo app not started\n");
+ warnx("not started");
}
exit(0);
@@ -144,7 +147,7 @@ int fixedwing_backside_main(int argc, char *argv[])
int control_demo_thread_main(int argc, char *argv[])
{
- printf("[control_Demo] starting\n");
+ warnx("starting");
using namespace control;
@@ -156,7 +159,7 @@ int control_demo_thread_main(int argc, char *argv[])
autopilot.update();
}
- printf("[control_demo] exiting.\n");
+ warnx("exiting.");
thread_running = false;
@@ -165,6 +168,6 @@ int control_demo_thread_main(int argc, char *argv[])
void test()
{
- printf("beginning control lib test\n");
+ warnx("beginning control lib test");
control::basicBlocksTest();
}
diff --git a/src/modules/fixedwing_backside/module.mk b/src/modules/fixedwing_backside/module.mk
index ec958d7cb..133728781 100644
--- a/src/modules/fixedwing_backside/module.mk
+++ b/src/modules/fixedwing_backside/module.mk
@@ -38,4 +38,5 @@
MODULE_COMMAND = fixedwing_backside
SRCS = fixedwing_backside_main.cpp \
+ fixedwing.cpp \
params.c
diff --git a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
index 48c0b9f9d..73df3fb9e 100644
--- a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
@@ -239,10 +239,10 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
parameters_init(&h);
parameters_update(&h, &p);
- pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE); //arbitrary high limit
- pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE);
- pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE);
- pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f * M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE); //TODO: remove hardcoded value
+ pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE, 0.0f); //arbitrary high limit
+ pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE, 0.0f);
+ pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE, 0.0f);
+ pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f * M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE, 0.0f); //TODO: remove hardcoded value
/* error and performance monitoring */
perf_counter_t fw_interval_perf = perf_alloc(PC_INTERVAL, "fixedwing_pos_control_interval");
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
new file mode 100644
index 000000000..60c902ce5
--- /dev/null
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -0,0 +1,782 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier
+ *
+ * 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 fw_att_control_main.c
+ * Implementation of a generic attitude controller based on classic orthogonal PIDs.
+ *
+ * @author Lorenz Meier <lm@inf.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 <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <systemlib/pid/pid.h>
+#include <geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+
+#include <ecl/attitude_fw/ecl_pitch_controller.h>
+#include <ecl/attitude_fw/ecl_roll_controller.h>
+#include <ecl/attitude_fw/ecl_yaw_controller.h>
+
+/**
+ * Fixedwing attitude control app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[]);
+
+class FixedwingAttitudeControl
+{
+public:
+ /**
+ * Constructor
+ */
+ FixedwingAttitudeControl();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~FixedwingAttitudeControl();
+
+ /**
+ * Start the sensors task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _control_task; /**< task handle for sensor task */
+
+ int _att_sub; /**< vehicle attitude subscription */
+ int _accel_sub; /**< accelerometer subscription */
+ int _att_sp_sub; /**< vehicle attitude setpoint */
+ int _attitude_sub; /**< raw rc channels data subscription */
+ int _airspeed_sub; /**< airspeed subscription */
+ int _vcontrol_mode_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_sub; /**< notification of manual control updates */
+
+ orb_advert_t _rate_sp_pub; /**< rate setpoint publication */
+ orb_advert_t _attitude_sp_pub; /**< attitude setpoint point */
+ orb_advert_t _actuators_0_pub; /**< actuator control group 0 setpoint */
+
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct accel_report _accel; /**< body frame accelerations */
+ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
+ struct manual_control_setpoint_s _manual; /**< r/c channel data */
+ struct airspeed_s _airspeed; /**< airspeed */
+ struct vehicle_control_mode_s _vcontrol_mode; /**< vehicle control mode */
+ struct actuator_controls_s _actuators; /**< actuator control inputs */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ bool _setpoint_valid; /**< flag if the position control setpoint is valid */
+ bool _airspeed_valid; /**< flag if the airspeed measurement is valid */
+
+ struct {
+ float tconst;
+ float p_p;
+ float p_d;
+ float p_i;
+ float p_rmax_pos;
+ float p_rmax_neg;
+ float p_integrator_max;
+ float p_roll_feedforward;
+ float r_p;
+ float r_d;
+ float r_i;
+ float r_integrator_max;
+ float r_rmax;
+ float y_p;
+ float y_i;
+ float y_d;
+ float y_roll_feedforward;
+ float y_integrator_max;
+
+ float airspeed_min;
+ float airspeed_trim;
+ float airspeed_max;
+ } _parameters; /**< local copies of interesting parameters */
+
+ struct {
+
+ param_t tconst;
+ param_t p_p;
+ param_t p_d;
+ param_t p_i;
+ param_t p_rmax_pos;
+ param_t p_rmax_neg;
+ param_t p_integrator_max;
+ param_t p_roll_feedforward;
+ param_t r_p;
+ param_t r_d;
+ param_t r_i;
+ param_t r_integrator_max;
+ param_t r_rmax;
+ param_t y_p;
+ param_t y_i;
+ param_t y_d;
+ param_t y_roll_feedforward;
+ param_t y_integrator_max;
+
+ param_t airspeed_min;
+ param_t airspeed_trim;
+ param_t airspeed_max;
+ } _parameter_handles; /**< handles for interesting parameters */
+
+
+ ECL_RollController _roll_ctrl;
+ ECL_PitchController _pitch_ctrl;
+ ECL_YawController _yaw_ctrl;
+
+
+ /**
+ * Update our local parameter cache.
+ */
+ int parameters_update();
+
+ /**
+ * Update control outputs
+ *
+ */
+ void control_update();
+
+ /**
+ * Check for changes in vehicle control mode.
+ */
+ void vehicle_control_mode_poll();
+
+ /**
+ * Check for changes in manual inputs.
+ */
+ void vehicle_manual_poll();
+
+
+ /**
+ * Check for airspeed updates.
+ */
+ bool vehicle_airspeed_poll();
+
+ /**
+ * Check for accel updates.
+ */
+ void vehicle_accel_poll();
+
+ /**
+ * Check for set triplet updates.
+ */
+ void vehicle_setpoint_poll();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main sensor collection task.
+ */
+ void task_main() __attribute__((noreturn));
+};
+
+namespace att_control
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+FixedwingAttitudeControl *g_control;
+}
+
+FixedwingAttitudeControl::FixedwingAttitudeControl() :
+
+ _task_should_exit(false),
+ _control_task(-1),
+
+/* subscriptions */
+ _att_sub(-1),
+ _accel_sub(-1),
+ _airspeed_sub(-1),
+ _vcontrol_mode_sub(-1),
+ _params_sub(-1),
+ _manual_sub(-1),
+
+/* publications */
+ _rate_sp_pub(-1),
+ _actuators_0_pub(-1),
+ _attitude_sp_pub(-1),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
+/* states */
+ _setpoint_valid(false),
+ _airspeed_valid(false)
+{
+ _parameter_handles.tconst = param_find("FW_ATT_TC");
+ _parameter_handles.p_p = param_find("FW_P_P");
+ _parameter_handles.p_d = param_find("FW_P_D");
+ _parameter_handles.p_i = param_find("FW_P_I");
+ _parameter_handles.p_rmax_pos = param_find("FW_P_RMAX_POS");
+ _parameter_handles.p_rmax_neg = param_find("FW_P_RMAX_NEG");
+ _parameter_handles.p_integrator_max = param_find("FW_P_IMAX");
+ _parameter_handles.p_roll_feedforward = param_find("FW_P_ROLLFF");
+
+ _parameter_handles.r_p = param_find("FW_R_P");
+ _parameter_handles.r_d = param_find("FW_R_D");
+ _parameter_handles.r_i = param_find("FW_R_I");
+ _parameter_handles.r_integrator_max = param_find("FW_R_IMAX");
+ _parameter_handles.r_rmax = param_find("FW_R_RMAX");
+
+ _parameter_handles.y_p = param_find("FW_Y_P");
+ _parameter_handles.y_i = param_find("FW_Y_I");
+ _parameter_handles.y_d = param_find("FW_Y_D");
+ _parameter_handles.y_roll_feedforward = param_find("FW_Y_ROLLFF");
+ _parameter_handles.y_integrator_max = param_find("FW_Y_IMAX");
+
+ _parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
+ _parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
+ _parameter_handles.airspeed_max = param_find("FW_AIRSPD_MAX");
+
+ /* fetch initial parameter values */
+ parameters_update();
+}
+
+FixedwingAttitudeControl::~FixedwingAttitudeControl()
+{
+ if (_control_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(_control_task);
+ break;
+ }
+ } while (_control_task != -1);
+ }
+
+ att_control::g_control = nullptr;
+}
+
+int
+FixedwingAttitudeControl::parameters_update()
+{
+
+ param_get(_parameter_handles.tconst, &(_parameters.tconst));
+ param_get(_parameter_handles.p_p, &(_parameters.p_p));
+ param_get(_parameter_handles.p_d, &(_parameters.p_d));
+ param_get(_parameter_handles.p_i, &(_parameters.p_i));
+ param_get(_parameter_handles.p_rmax_pos, &(_parameters.p_rmax_pos));
+ param_get(_parameter_handles.p_rmax_neg, &(_parameters.p_rmax_neg));
+ param_get(_parameter_handles.p_integrator_max, &(_parameters.p_integrator_max));
+ param_get(_parameter_handles.p_roll_feedforward, &(_parameters.p_roll_feedforward));
+
+ param_get(_parameter_handles.r_p, &(_parameters.r_p));
+ param_get(_parameter_handles.r_d, &(_parameters.r_d));
+ param_get(_parameter_handles.r_i, &(_parameters.r_i));
+ param_get(_parameter_handles.r_integrator_max, &(_parameters.r_integrator_max));
+ param_get(_parameter_handles.r_rmax, &(_parameters.r_rmax));
+
+ param_get(_parameter_handles.y_p, &(_parameters.y_p));
+ param_get(_parameter_handles.y_i, &(_parameters.y_i));
+ param_get(_parameter_handles.y_d, &(_parameters.y_d));
+ param_get(_parameter_handles.y_roll_feedforward, &(_parameters.y_roll_feedforward));
+ param_get(_parameter_handles.y_integrator_max, &(_parameters.y_integrator_max));
+
+ param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
+ param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
+ param_get(_parameter_handles.airspeed_max, &(_parameters.airspeed_max));
+
+ /* pitch control parameters */
+ _pitch_ctrl.set_time_constant(_parameters.tconst);
+ _pitch_ctrl.set_k_p(math::radians(_parameters.p_p));
+ _pitch_ctrl.set_k_i(math::radians(_parameters.p_i));
+ _pitch_ctrl.set_k_d(math::radians(_parameters.p_d));
+ _pitch_ctrl.set_integrator_max(math::radians(_parameters.p_integrator_max));
+ _pitch_ctrl.set_max_rate_pos(math::radians(_parameters.p_rmax_pos));
+ _pitch_ctrl.set_max_rate_neg(math::radians(_parameters.p_rmax_neg));
+ _pitch_ctrl.set_roll_ff(math::radians(_parameters.p_roll_feedforward));
+
+ /* roll control parameters */
+ _roll_ctrl.set_time_constant(_parameters.tconst);
+ _roll_ctrl.set_k_p(math::radians(_parameters.r_p));
+ _roll_ctrl.set_k_i(math::radians(_parameters.r_i));
+ _roll_ctrl.set_k_d(math::radians(_parameters.r_d));
+ _roll_ctrl.set_integrator_max(math::radians(_parameters.r_integrator_max));
+ _roll_ctrl.set_max_rate(math::radians(_parameters.r_rmax));
+
+ /* yaw control parameters */
+ _yaw_ctrl.set_k_side(math::radians(_parameters.y_p));
+ _yaw_ctrl.set_k_i(math::radians(_parameters.y_i));
+ _yaw_ctrl.set_k_d(math::radians(_parameters.y_d));
+ _yaw_ctrl.set_k_roll_ff(math::radians(_parameters.y_roll_feedforward));
+ _yaw_ctrl.set_integrator_max(math::radians(_parameters.y_integrator_max));
+
+ return OK;
+}
+
+void
+FixedwingAttitudeControl::vehicle_control_mode_poll()
+{
+ bool vcontrol_mode_updated;
+
+ /* Check HIL state if vehicle status has changed */
+ orb_check(_vcontrol_mode_sub, &vcontrol_mode_updated);
+
+ if (vcontrol_mode_updated) {
+
+ orb_copy(ORB_ID(vehicle_control_mode), _vcontrol_mode_sub, &_vcontrol_mode);
+ }
+}
+
+void
+FixedwingAttitudeControl::vehicle_manual_poll()
+{
+ bool manual_updated;
+
+ /* get pilots inputs */
+ orb_check(_manual_sub, &manual_updated);
+
+ if (manual_updated) {
+
+ orb_copy(ORB_ID(manual_control_setpoint), _manual_sub, &_manual);
+ }
+}
+
+bool
+FixedwingAttitudeControl::vehicle_airspeed_poll()
+{
+ /* check if there is a new position */
+ bool airspeed_updated;
+ orb_check(_airspeed_sub, &airspeed_updated);
+
+ if (airspeed_updated) {
+ orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
+ return true;
+ }
+
+ return false;
+}
+
+void
+FixedwingAttitudeControl::vehicle_accel_poll()
+{
+ /* check if there is a new position */
+ bool accel_updated;
+ orb_check(_accel_sub, &accel_updated);
+
+ if (accel_updated) {
+ orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ }
+}
+
+void
+FixedwingAttitudeControl::vehicle_setpoint_poll()
+{
+ /* check if there is a new setpoint */
+ bool att_sp_updated;
+ orb_check(_att_sp_sub, &att_sp_updated);
+
+ if (att_sp_updated) {
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), _att_sp_sub, &_att_sp);
+ _setpoint_valid = true;
+ }
+}
+
+void
+FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[])
+{
+ att_control::g_control->task_main();
+}
+
+void
+FixedwingAttitudeControl::task_main()
+{
+
+ /* inform about start */
+ warnx("Initializing..");
+ fflush(stdout);
+
+ /*
+ * do subscriptions
+ */
+ _att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ _accel_sub = orb_subscribe(ORB_ID(sensor_accel));
+ _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ _params_sub = orb_subscribe(ORB_ID(parameter_update));
+ _manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_vcontrol_mode_sub, 200);
+ /* rate limit attitude control to 50 Hz (with some margin, so 17 ms) */
+ orb_set_interval(_att_sub, 17);
+
+ parameters_update();
+
+ /* get an initial update for all sensor and status data */
+ (void)vehicle_airspeed_poll();
+ vehicle_setpoint_poll();
+ vehicle_accel_poll();
+ vehicle_control_mode_poll();
+ vehicle_manual_poll();
+
+ /* wakeup source(s) */
+ struct pollfd fds[2];
+
+ /* Setup of loop */
+ fds[0].fd = _params_sub;
+ fds[0].events = POLLIN;
+ fds[1].fd = _att_sub;
+ fds[1].events = POLLIN;
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 500ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+
+ /* timed out - periodic check for _task_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* 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;
+ }
+
+ perf_begin(_loop_perf);
+
+ /* only update parameters if they changed */
+ if (fds[0].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+
+ /* update parameters from storage */
+ parameters_update();
+ }
+
+ /* only run controller if attitude changed */
+ if (fds[1].revents & POLLIN) {
+
+
+ static uint64_t last_run = 0;
+ float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+ /* guard against too large deltaT's */
+ if (deltaT > 1.0f)
+ deltaT = 0.01f;
+
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+
+ _airspeed_valid = vehicle_airspeed_poll();
+
+ vehicle_setpoint_poll();
+
+ vehicle_accel_poll();
+
+ vehicle_control_mode_poll();
+
+ vehicle_manual_poll();
+
+ /* lock integrator until control is started */
+ bool lock_integrator;
+
+ if (_vcontrol_mode.flag_control_attitude_enabled) {
+ lock_integrator = false;
+
+ } else {
+ lock_integrator = true;
+ }
+
+ /* decide if in stabilized or full manual control */
+
+ if (_vcontrol_mode.flag_control_attitude_enabled) {
+
+ /* scale from radians to normalized -1 .. 1 range */
+ const float actuator_scaling = 1.0f / (M_PI_F / 4.0f);
+
+ /* scale around tuning airspeed */
+
+ float airspeed;
+
+ /* if airspeed is smaller than min, the sensor is not giving good readings */
+ if (!_airspeed_valid ||
+ (_airspeed.indicated_airspeed_m_s < _parameters.airspeed_min) ||
+ !isfinite(_airspeed.indicated_airspeed_m_s)) {
+ airspeed = _parameters.airspeed_min + (_parameters.airspeed_max - _parameters.airspeed_min) / 2.0f;
+
+ } else {
+ airspeed = _airspeed.indicated_airspeed_m_s;
+ }
+
+ float airspeed_scaling = _parameters.airspeed_trim / airspeed;
+ //warnx("aspd scale: %6.2f act scale: %6.2f", airspeed_scaling, actuator_scaling);
+
+ float roll_sp, pitch_sp;
+ float throttle_sp = 0.0f;
+
+ if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
+ roll_sp = _att_sp.roll_body;
+ pitch_sp = _att_sp.pitch_body;
+ throttle_sp = _att_sp.thrust;
+
+ /* reset integrals where needed */
+ if (_att_sp.roll_reset_integral)
+ _roll_ctrl.reset_integrator();
+
+ } else {
+ /*
+ * Scale down roll and pitch as the setpoints are radians
+ * and a typical remote can only do 45 degrees, the mapping is
+ * -1..+1 to -45..+45 degrees or -0.75..+0.75 radians.
+ *
+ * With this mapping the stick angle is a 1:1 representation of
+ * the commanded attitude. If more than 45 degrees are desired,
+ * a scaling parameter can be applied to the remote.
+ */
+ roll_sp = _manual.roll * 0.75f;
+ pitch_sp = _manual.pitch * 0.75f;
+ throttle_sp = _manual.throttle;
+ _actuators.control[4] = _manual.flaps;
+
+ /*
+ * in manual mode no external source should / does emit attitude setpoints.
+ * emit the manual setpoint here to allow attitude controller tuning
+ * in attitude control mode.
+ */
+ struct vehicle_attitude_setpoint_s att_sp;
+ att_sp.timestamp = hrt_absolute_time();
+ att_sp.roll_body = roll_sp;
+ att_sp.pitch_body = pitch_sp;
+ att_sp.yaw_body = 0.0f;
+ att_sp.thrust = throttle_sp;
+
+ /* lazily publish the setpoint only once available */
+ if (_attitude_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _attitude_sp_pub, &att_sp);
+
+ } else {
+ /* advertise and publish */
+ _attitude_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
+ }
+ }
+
+ if (isfinite(roll_sp) && isfinite(pitch_sp)) {
+
+ float roll_rad = _roll_ctrl.control(roll_sp, _att.roll, _att.rollspeed,
+ airspeed_scaling, lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
+ _actuators.control[0] = (isfinite(roll_rad)) ? roll_rad * actuator_scaling : 0.0f;
+
+ float pitch_rad = _pitch_ctrl.control(pitch_sp, _att.pitch, _att.pitchspeed, _att.roll, airspeed_scaling,
+ lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
+ _actuators.control[1] = (isfinite(pitch_rad)) ? pitch_rad * actuator_scaling : 0.0f;
+
+ float yaw_rad = _yaw_ctrl.control(_att.roll, _att.yawspeed, _accel.y, airspeed_scaling, lock_integrator,
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
+ _actuators.control[2] = (isfinite(yaw_rad)) ? yaw_rad * actuator_scaling : 0.0f;
+
+ /* throttle passed through */
+ _actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
+
+ // warnx("aspd: %s: %6.2f, aspd scaling: %6.2f, controls: %5.2f %5.2f %5.2f %5.2f", (_airspeed_valid) ? "valid" : "unknown",
+ // airspeed, airspeed_scaling, _actuators.control[0], _actuators.control[1],
+ // _actuators.control[2], _actuators.control[3]);
+
+ /*
+ * Lazily publish the rate setpoint (for analysis, the actuators are published below)
+ * only once available
+ */
+ vehicle_rates_setpoint_s rates_sp;
+ rates_sp.roll = _roll_ctrl.get_desired_rate();
+ rates_sp.pitch = _pitch_ctrl.get_desired_rate();
+ rates_sp.yaw = 0.0f; // XXX not yet implemented
+
+ rates_sp.timestamp = hrt_absolute_time();
+
+ if (_rate_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
+
+ } else {
+ /* advertise and publish */
+ _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
+ }
+ }
+
+ } else {
+ /* manual/direct control */
+ _actuators.control[0] = _manual.roll;
+ _actuators.control[1] = _manual.pitch;
+ _actuators.control[2] = _manual.yaw;
+ _actuators.control[3] = _manual.throttle;
+ _actuators.control[4] = _manual.flaps;
+ }
+
+ _actuators.control[5] = _manual.aux1;
+ _actuators.control[6] = _manual.aux2;
+ _actuators.control[7] = _manual.aux3;
+
+ /* lazily publish the setpoint only once available */
+ _actuators.timestamp = hrt_absolute_time();
+
+ if (_actuators_0_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators);
+
+ } else {
+ /* advertise and publish */
+ _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators);
+ }
+
+ }
+
+ perf_end(_loop_perf);
+ }
+
+ warnx("exiting.\n");
+
+ _control_task = -1;
+ _exit(0);
+}
+
+int
+FixedwingAttitudeControl::start()
+{
+ ASSERT(_control_task == -1);
+
+ /* start the task */
+ _control_task = task_spawn_cmd("fw_att_control",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&FixedwingAttitudeControl::task_main_trampoline,
+ nullptr);
+
+ if (_control_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int fw_att_control_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: fw_att_control {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (att_control::g_control != nullptr)
+ errx(1, "already running");
+
+ att_control::g_control = new FixedwingAttitudeControl;
+
+ if (att_control::g_control == nullptr)
+ errx(1, "alloc failed");
+
+ if (OK != att_control::g_control->start()) {
+ delete att_control::g_control;
+ att_control::g_control = nullptr;
+ err(1, "start failed");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (att_control::g_control == nullptr)
+ errx(1, "not running");
+
+ delete att_control::g_control;
+ att_control::g_control = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (att_control::g_control) {
+ errx(0, "running");
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
new file mode 100644
index 000000000..be76524da
--- /dev/null
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -0,0 +1,136 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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 fw_att_control_params.c
+ *
+ * Parameters defined by the fixed-wing attitude control task
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Controller parameters, accessible via MAVLink
+ *
+ */
+
+// @DisplayName Attitude Time Constant
+// @Description This defines the latency between a step input and the achieved setpoint. Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
+// @Range 0.4 to 1.0 seconds, in tens of seconds
+PARAM_DEFINE_FLOAT(FW_ATT_TC, 0.5f);
+
+// @DisplayName Proportional gain.
+// @Description This defines how much the elevator input will be commanded dependend on the current pitch error.
+// @Range 10 to 200, 1 increments
+PARAM_DEFINE_FLOAT(FW_P_P, 40.0f);
+
+// @DisplayName Damping gain.
+// @Description This gain damps the airframe pitch rate. In particular relevant for flying wings.
+// @Range 0.0 to 10.0, 0.1 increments
+PARAM_DEFINE_FLOAT(FW_P_D, 0.0f);
+
+// @DisplayName Integrator gain.
+// @Description This gain defines how much control response will result out of a steady state error. It trims any constant error.
+// @Range 0 to 50.0
+PARAM_DEFINE_FLOAT(FW_P_I, 0.0f);
+
+// @DisplayName Maximum positive / up pitch rate.
+// @Description This limits the maximum pitch up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
+// @Range 0 to 90.0 degrees per seconds, in 1 increments
+PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 0.0f);
+
+// @DisplayName Maximum negative / down pitch rate.
+// @Description This limits the maximum pitch down up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
+// @Range 0 to 90.0 degrees per seconds, in 1 increments
+PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 0.0f);
+
+// @DisplayName Pitch Integrator Anti-Windup
+// @Description This limits the range in degrees the integrator can wind up to.
+// @Range 0.0 to 45.0
+// @Increment 1.0
+PARAM_DEFINE_FLOAT(FW_P_IMAX, 15.0f);
+
+// @DisplayName Roll feedforward gain.
+// @Description This compensates during turns and ensures the nose stays level.
+// @Range 0.5 2.0
+// @Increment 0.05
+// @User User
+PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 1.0f);
+
+// @DisplayName Proportional Gain.
+// @Description This gain controls the roll angle to roll actuator output.
+// @Range 10.0 200.0
+// @Increment 10.0
+// @User User
+PARAM_DEFINE_FLOAT(FW_R_P, 40.0f);
+
+// @DisplayName Damping Gain
+// @Description Controls the roll rate to roll actuator output. It helps to reduce motions in turbulence.
+// @Range 0.0 10.0
+// @Increment 1.0
+// @User User
+PARAM_DEFINE_FLOAT(FW_R_D, 0.0f);
+
+// @DisplayName Integrator Gain
+// @Description This gain controls the contribution of the integral to roll actuator outputs. It trims out steady state errors.
+// @Range 0.0 100.0
+// @Increment 5.0
+// @User User
+PARAM_DEFINE_FLOAT(FW_R_I, 0.0f);
+
+// @DisplayName Roll Integrator Anti-Windup
+// @Description This limits the range in degrees the integrator can wind up to.
+// @Range 0.0 to 45.0
+// @Increment 1.0
+PARAM_DEFINE_FLOAT(FW_R_IMAX, 15.0f);
+
+// @DisplayName Maximum Roll Rate
+// @Description This limits the maximum roll rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
+// @Range 0 to 90.0 degrees per seconds
+// @Increment 1.0
+PARAM_DEFINE_FLOAT(FW_R_RMAX, 60);
+
+
+PARAM_DEFINE_FLOAT(FW_Y_P, 0);
+PARAM_DEFINE_FLOAT(FW_Y_I, 0);
+PARAM_DEFINE_FLOAT(FW_Y_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_Y_D, 0);
+PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 1);
+PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 9.0f);
+PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 12.0f);
+PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 18.0f);
diff --git a/src/modules/fw_att_control/module.mk b/src/modules/fw_att_control/module.mk
new file mode 100644
index 000000000..1e600757e
--- /dev/null
+++ b/src/modules/fw_att_control/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Fixedwing attitude control application
+#
+
+MODULE_COMMAND = fw_att_control
+
+SRCS = fw_att_control_main.cpp \
+ fw_att_control_params.c
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
new file mode 100644
index 000000000..a9648b207
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -0,0 +1,1217 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier
+ *
+ * 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 fw_pos_control_l1_main.c
+ * Implementation of a generic position controller based on the L1 norm. Outputs a bank / roll
+ * angle, equivalent to a lateral motion (for copters and rovers).
+ *
+ * Original publication for horizontal control class:
+ * S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
+ * Proceedings of the AIAA Guidance, Navigation and Control
+ * Conference, Aug 2004. AIAA-2004-4900.
+ *
+ * Original implementation for total energy control class:
+ * Paul Riseborough and Andrew Tridgell, 2013 (code in lib/external_lgpl)
+ *
+ * More details and acknowledgements in the referenced library headers.
+ *
+ * @author Lorenz Meier <lm@inf.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 <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/navigation_capabilities.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <systemlib/pid/pid.h>
+#include <geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+
+#include <ecl/l1/ecl_l1_pos_controller.h>
+#include <external_lgpl/tecs/tecs.h>
+
+/**
+ * L1 control app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]);
+
+class FixedwingPositionControl
+{
+public:
+ /**
+ * Constructor
+ */
+ FixedwingPositionControl();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~FixedwingPositionControl();
+
+ /**
+ * Start the sensors task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _control_task; /**< task handle for sensor task */
+
+ int _global_pos_sub;
+ int _global_set_triplet_sub;
+ int _att_sub; /**< vehicle attitude subscription */
+ int _attitude_sub; /**< raw rc channels data subscription */
+ int _airspeed_sub; /**< airspeed subscription */
+ int _control_mode_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_control_sub; /**< notification of manual control updates */
+ int _accel_sub; /**< body frame accelerations */
+
+ orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
+ orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */
+
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
+ 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_global_position_s _global_pos; /**< global vehicle position */
+ struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct accel_report _accel; /**< body frame accelerations */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ bool _setpoint_valid; /**< flag if the position control setpoint is valid */
+
+ /** manual control states */
+ float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
+ float _loiter_hold_lat;
+ float _loiter_hold_lon;
+ float _loiter_hold_alt;
+ bool _loiter_hold;
+
+ float _launch_lat;
+ float _launch_lon;
+ float _launch_alt;
+ bool _launch_valid;
+
+ /* land states */
+ /* not in non-abort mode for landing yet */
+ bool land_noreturn;
+ /* heading hold */
+ float target_bearing;
+
+ /* throttle and airspeed states */
+ float _airspeed_error; ///< airspeed error to setpoint in m/s
+ bool _airspeed_valid; ///< flag if a valid airspeed estimate exists
+ uint64_t _airspeed_last_valid; ///< last time airspeed was valid. Used to detect sensor failures
+ float _groundspeed_undershoot; ///< ground speed error to min. speed in m/s
+ bool _global_pos_valid; ///< global position is valid
+ math::Dcm _R_nb; ///< current attitude
+
+ ECL_L1_Pos_Controller _l1_control;
+ TECS _tecs;
+
+ struct {
+ float l1_period;
+ float l1_damping;
+
+ float time_const;
+ float min_sink_rate;
+ float max_sink_rate;
+ float max_climb_rate;
+ float throttle_damp;
+ float integrator_gain;
+ float vertical_accel_limit;
+ float height_comp_filter_omega;
+ float speed_comp_filter_omega;
+ float roll_throttle_compensation;
+ float speed_weight;
+ float pitch_damping;
+
+ float airspeed_min;
+ float airspeed_trim;
+ float airspeed_max;
+
+ float pitch_limit_min;
+ float pitch_limit_max;
+ float roll_limit;
+ float throttle_min;
+ float throttle_max;
+ float throttle_cruise;
+
+ float throttle_land_max;
+
+ float loiter_hold_radius;
+ } _parameters; /**< local copies of interesting parameters */
+
+ struct {
+
+ param_t l1_period;
+ param_t l1_damping;
+
+ param_t time_const;
+ param_t min_sink_rate;
+ param_t max_sink_rate;
+ param_t max_climb_rate;
+ param_t throttle_damp;
+ param_t integrator_gain;
+ param_t vertical_accel_limit;
+ param_t height_comp_filter_omega;
+ param_t speed_comp_filter_omega;
+ param_t roll_throttle_compensation;
+ param_t speed_weight;
+ param_t pitch_damping;
+
+ param_t airspeed_min;
+ param_t airspeed_trim;
+ param_t airspeed_max;
+
+ param_t pitch_limit_min;
+ param_t pitch_limit_max;
+ param_t roll_limit;
+ param_t throttle_min;
+ param_t throttle_max;
+ param_t throttle_cruise;
+
+ param_t throttle_land_max;
+
+ param_t loiter_hold_radius;
+ } _parameter_handles; /**< handles for interesting parameters */
+
+
+ /**
+ * Update our local parameter cache.
+ */
+ int parameters_update();
+
+ /**
+ * Update control outputs
+ *
+ */
+ void control_update();
+
+ /**
+ * Check for changes in vehicle status.
+ */
+ void vehicle_control_mode_poll();
+
+ /**
+ * Check for airspeed updates.
+ */
+ bool vehicle_airspeed_poll();
+
+ /**
+ * Check for position updates.
+ */
+ void vehicle_attitude_poll();
+
+ /**
+ * Check for accel updates.
+ */
+ void vehicle_accel_poll();
+
+ /**
+ * Check for set triplet updates.
+ */
+ void vehicle_setpoint_poll();
+
+ /**
+ * Control position.
+ */
+ bool control_position(const math::Vector2f &global_pos, const math::Vector2f &ground_speed,
+ const struct vehicle_global_position_set_triplet_s &global_triplet);
+
+ float calculate_target_airspeed(float airspeed_demand);
+ void calculate_gndspeed_undershoot();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main sensor collection task.
+ */
+ void task_main() __attribute__((noreturn));
+};
+
+namespace l1_control
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+FixedwingPositionControl *g_control;
+}
+
+FixedwingPositionControl::FixedwingPositionControl() :
+
+ _task_should_exit(false),
+ _control_task(-1),
+
+/* subscriptions */
+ _global_pos_sub(-1),
+ _global_set_triplet_sub(-1),
+ _att_sub(-1),
+ _airspeed_sub(-1),
+ _control_mode_sub(-1),
+ _params_sub(-1),
+ _manual_control_sub(-1),
+
+/* publications */
+ _attitude_sp_pub(-1),
+ _nav_capabilities_pub(-1),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
+/* states */
+ _setpoint_valid(false),
+ _loiter_hold(false),
+ _airspeed_error(0.0f),
+ _airspeed_valid(false),
+ _groundspeed_undershoot(0.0f),
+ _global_pos_valid(false),
+ land_noreturn(false)
+{
+ _nav_capabilities.turn_distance = 0.0f;
+
+ _parameter_handles.l1_period = param_find("FW_L1_PERIOD");
+ _parameter_handles.l1_damping = param_find("FW_L1_DAMPING");
+ _parameter_handles.loiter_hold_radius = param_find("FW_LOITER_R");
+
+ _parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
+ _parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
+ _parameter_handles.airspeed_max = param_find("FW_AIRSPD_MAX");
+
+ _parameter_handles.pitch_limit_min = param_find("FW_P_LIM_MIN");
+ _parameter_handles.pitch_limit_max = param_find("FW_P_LIM_MAX");
+ _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_cruise = param_find("FW_THR_CRUISE");
+ _parameter_handles.throttle_land_max = param_find("FW_THR_LND_MAX");
+
+ _parameter_handles.time_const = param_find("FW_T_TIME_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.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");
+ _parameter_handles.height_comp_filter_omega = param_find("FW_T_HGT_OMEGA");
+ _parameter_handles.speed_comp_filter_omega = param_find("FW_T_SPD_OMEGA");
+ _parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR");
+ _parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
+ _parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
+
+ /* fetch initial parameter values */
+ parameters_update();
+}
+
+FixedwingPositionControl::~FixedwingPositionControl()
+{
+ if (_control_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(_control_task);
+ break;
+ }
+ } while (_control_task != -1);
+ }
+
+ l1_control::g_control = nullptr;
+}
+
+int
+FixedwingPositionControl::parameters_update()
+{
+
+ /* L1 control parameters */
+ param_get(_parameter_handles.l1_damping, &(_parameters.l1_damping));
+ param_get(_parameter_handles.l1_period, &(_parameters.l1_period));
+ param_get(_parameter_handles.loiter_hold_radius, &(_parameters.loiter_hold_radius));
+
+ param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
+ param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
+ param_get(_parameter_handles.airspeed_max, &(_parameters.airspeed_max));
+
+ param_get(_parameter_handles.pitch_limit_min, &(_parameters.pitch_limit_min));
+ param_get(_parameter_handles.pitch_limit_max, &(_parameters.pitch_limit_max));
+ param_get(_parameter_handles.roll_limit, &(_parameters.roll_limit));
+ 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_land_max, &(_parameters.throttle_land_max));
+
+ param_get(_parameter_handles.time_const, &(_parameters.time_const));
+ 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));
+ param_get(_parameter_handles.integrator_gain, &(_parameters.integrator_gain));
+ param_get(_parameter_handles.vertical_accel_limit, &(_parameters.vertical_accel_limit));
+ param_get(_parameter_handles.height_comp_filter_omega, &(_parameters.height_comp_filter_omega));
+ param_get(_parameter_handles.speed_comp_filter_omega, &(_parameters.speed_comp_filter_omega));
+ param_get(_parameter_handles.roll_throttle_compensation, &(_parameters.roll_throttle_compensation));
+ 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));
+
+ _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_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_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);
+ _tecs.set_speed_comp_filter_omega(_parameters.speed_comp_filter_omega);
+ _tecs.set_roll_throttle_compensation(math::radians(_parameters.roll_throttle_compensation));
+ _tecs.set_speed_weight(_parameters.speed_weight);
+ _tecs.set_pitch_damping(_parameters.pitch_damping);
+ _tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
+ _tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
+ _tecs.set_max_climb_rate(_parameters.max_climb_rate);
+
+ /* sanity check parameters */
+ if (_parameters.airspeed_max < _parameters.airspeed_min ||
+ _parameters.airspeed_max < 5.0f ||
+ _parameters.airspeed_min > 100.0f ||
+ _parameters.airspeed_trim < _parameters.airspeed_min ||
+ _parameters.airspeed_trim > _parameters.airspeed_max) {
+ warnx("error: airspeed parameters invalid");
+ return 1;
+ }
+
+ return OK;
+}
+
+void
+FixedwingPositionControl::vehicle_control_mode_poll()
+{
+ bool vstatus_updated;
+
+ /* Check HIL state if vehicle status has changed */
+ orb_check(_control_mode_sub, &vstatus_updated);
+
+ if (vstatus_updated) {
+
+ bool was_armed = _control_mode.flag_armed;
+
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+
+ if (!was_armed && _control_mode.flag_armed) {
+ _launch_lat = _global_pos.lat / 1e7f;
+ _launch_lon = _global_pos.lon / 1e7f;
+ _launch_alt = _global_pos.alt;
+ _launch_valid = true;
+ }
+ }
+}
+
+bool
+FixedwingPositionControl::vehicle_airspeed_poll()
+{
+ /* check if there is an airspeed update or if it timed out */
+ bool airspeed_updated;
+ orb_check(_airspeed_sub, &airspeed_updated);
+
+ if (airspeed_updated) {
+ orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
+ _airspeed_valid = true;
+ _airspeed_last_valid = hrt_absolute_time();
+
+ } else {
+
+ /* no airspeed updates for one second */
+ if (_airspeed_valid && (hrt_absolute_time() - _airspeed_last_valid) > 1e6) {
+ _airspeed_valid = false;
+ }
+ }
+
+ /* update TECS state */
+ _tecs.enable_airspeed(_airspeed_valid);
+
+ return airspeed_updated;
+}
+
+void
+FixedwingPositionControl::vehicle_attitude_poll()
+{
+ /* check if there is a new position */
+ bool att_updated;
+ orb_check(_att_sub, &att_updated);
+
+ if (att_updated) {
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+
+ /* set rotation matrix */
+ for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
+ _R_nb(i, j) = _att.R[i][j];
+ }
+}
+
+void
+FixedwingPositionControl::vehicle_accel_poll()
+{
+ /* check if there is a new position */
+ bool accel_updated;
+ orb_check(_accel_sub, &accel_updated);
+
+ if (accel_updated) {
+ orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ }
+}
+
+void
+FixedwingPositionControl::vehicle_setpoint_poll()
+{
+ /* check if there is a new setpoint */
+ bool global_sp_updated;
+ orb_check(_global_set_triplet_sub, &global_sp_updated);
+
+ if (global_sp_updated) {
+ orb_copy(ORB_ID(vehicle_global_position_set_triplet), _global_set_triplet_sub, &_global_triplet);
+ _setpoint_valid = true;
+ }
+}
+
+void
+FixedwingPositionControl::task_main_trampoline(int argc, char *argv[])
+{
+ l1_control::g_control->task_main();
+}
+
+float
+FixedwingPositionControl::calculate_target_airspeed(float airspeed_demand)
+{
+ float airspeed;
+
+ if (_airspeed_valid) {
+ airspeed = _airspeed.true_airspeed_m_s;
+
+ } else {
+ airspeed = _parameters.airspeed_min + (_parameters.airspeed_max - _parameters.airspeed_min) / 2.0f;
+ }
+
+ /* cruise airspeed for all modes unless modified below */
+ float target_airspeed = airspeed_demand;
+
+ /* add minimum ground speed undershoot (only non-zero in presence of sufficient wind) */
+ target_airspeed += _groundspeed_undershoot;
+
+ if (0/* throttle nudging enabled */) {
+ //target_airspeed += nudge term.
+ }
+
+ /* sanity check: limit to range */
+ target_airspeed = math::constrain(target_airspeed, _parameters.airspeed_min, _parameters.airspeed_max);
+
+ /* plain airspeed error */
+ _airspeed_error = target_airspeed - airspeed;
+
+ return target_airspeed;
+}
+
+void
+FixedwingPositionControl::calculate_gndspeed_undershoot()
+{
+
+ if (_global_pos_valid) {
+ /* get ground speed vector */
+ math::Vector2f ground_speed_vector(_global_pos.vx, _global_pos.vy);
+
+ /* rotate with current attitude */
+ math::Vector2f yaw_vector(_R_nb(0, 0), _R_nb(1, 0));
+ yaw_vector.normalize();
+ float ground_speed_body = yaw_vector * ground_speed_vector;
+
+ /*
+ * Ground speed undershoot is the amount of ground velocity not reached
+ * by the plane. Consequently it is zero if airspeed is >= min ground speed
+ * and positive if airspeed < min ground speed.
+ *
+ * This error value ensures that a plane (as long as its throttle capability is
+ * not exceeded) travels towards a waypoint (and is not pushed more and more away
+ * by wind). Not countering this would lead to a fly-away.
+ */
+ _groundspeed_undershoot = math::max(_parameters.airspeed_min - ground_speed_body, 0.0f);
+
+ } else {
+ _groundspeed_undershoot = 0;
+ }
+}
+
+bool
+FixedwingPositionControl::control_position(const math::Vector2f &current_position, const math::Vector2f &ground_speed,
+ const struct vehicle_global_position_set_triplet_s &global_triplet)
+{
+ bool setpoint = true;
+
+ calculate_gndspeed_undershoot();
+
+ float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
+
+ // XXX re-visit
+ float baro_altitude = _global_pos.alt;
+
+ /* filter speed and altitude for controller */
+ math::Vector3 accel_body(_accel.x, _accel.y, _accel.z);
+ math::Vector3 accel_earth = _R_nb.transpose() * accel_body;
+
+ _tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
+ float altitude_error = _global_triplet.current.altitude - _global_pos.alt;
+
+ /* no throttle limit as default */
+ float throttle_max = 1.0f;
+
+ /* AUTONOMOUS FLIGHT */
+
+ // XXX this should only execute if auto AND safety off (actuators active),
+ // else integrators should be constantly reset.
+ if (_control_mode.flag_control_position_enabled) {
+
+ /* get circle mode */
+ bool was_circle_mode = _l1_control.circle_mode();
+
+ /* restore speed weight, in case changed intermittently (e.g. in landing handling) */
+ _tecs.set_speed_weight(_parameters.speed_weight);
+
+ /* execute navigation once we have a setpoint */
+ if (_setpoint_valid) {
+
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f next_wp(global_triplet.current.lat / 1e7f, global_triplet.current.lon / 1e7f);
+
+ /* previous waypoint */
+ math::Vector2f prev_wp;
+
+ if (global_triplet.previous_valid) {
+ prev_wp.setX(global_triplet.previous.lat / 1e7f);
+ prev_wp.setY(global_triplet.previous.lon / 1e7f);
+
+ } else {
+ /*
+ * No valid previous waypoint, go for the current wp.
+ * This is automatically handled by the L1 library.
+ */
+ prev_wp.setX(global_triplet.current.lat / 1e7f);
+ prev_wp.setY(global_triplet.current.lon / 1e7f);
+
+ }
+
+ // XXX add RTL switch
+ if (global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH && _launch_valid) {
+
+ math::Vector2f rtl_pos(_launch_lat, _launch_lon);
+
+ _l1_control.navigate_waypoints(rtl_pos, rtl_pos, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _launch_alt, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ // XXX handle case when having arrived at home (loiter)
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
+ /* waypoint is a plain navigation waypoint */
+ _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+
+ /* waypoint is a loiter waypoint */
+ _l1_control.navigate_loiter(next_wp, current_position, global_triplet.current.loiter_radius,
+ global_triplet.current.loiter_direction, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_LAND) {
+
+ /* switch to heading hold for the last meters, continue heading hold after */
+
+ float wp_distance = get_distance_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), current_position.getX(), current_position.getY());
+ //warnx("wp dist: %d, alt err: %d, noret: %s", (int)wp_distance, (int)altitude_error, (land_noreturn) ? "YES" : "NO");
+ if (wp_distance < 15.0f || land_noreturn) {
+
+ /* heading hold, along the line connecting this and the last waypoint */
+
+
+ // if (global_triplet.previous_valid) {
+ // target_bearing = get_bearing_to_next_waypoint(prev_wp.getX(), prev_wp.getY(), next_wp.getX(), next_wp.getY());
+ // } else {
+
+ if (!land_noreturn)
+ target_bearing = _att.yaw;
+ //}
+
+ warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
+
+ _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
+
+ if (altitude_error > -5.0f)
+ land_noreturn = true;
+
+ } else {
+
+ /* normal navigation */
+ _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
+ }
+
+ /* do not go down too early */
+ if (wp_distance > 50.0f) {
+ altitude_error = (_global_triplet.current.altitude + 25.0f) - _global_pos.alt;
+ }
+
+
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ /* 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_angle_rad = math::radians(10.0f);//math::radians(global_triplet.current.param1)
+ float land_pitch_min = math::radians(5.0f);
+ float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
+ float airspeed_land = _parameters.airspeed_min;
+ float airspeed_approach = (_parameters.airspeed_min + _parameters.airspeed_trim) / 2.0f;
+
+ if (altitude_error > -4.0f) {
+
+ /* land with minimal speed */
+
+ /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
+ _tecs.set_speed_weight(2.0f);
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(airspeed_land),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, flare_angle_rad,
+ 0.0f, _parameters.throttle_max, throttle_land,
+ math::radians(-10.0f), math::radians(15.0f));
+
+ /* kill the throttle if param requests it */
+ throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
+
+ /* limit roll motion to prevent wings from touching the ground first */
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-10.0f), math::radians(10.0f));
+
+ } else if (wp_distance < 60.0f && altitude_error > -20.0f) {
+
+ /* minimize speed to approach speed */
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(airspeed_approach),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, flare_angle_rad,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ } else {
+
+ /* normal cruise speed */
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ }
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+
+ _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
+ if (altitude_error > 10.0f) {
+
+ /* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_min),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ true, math::max(math::radians(global_triplet.current.param1), math::radians(10.0f)),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_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));
+
+ } else {
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ }
+ }
+
+ // warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(),
+ // (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing());
+ // warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp.getX(), (double)prev_wp.getY(),
+ // (double)next_wp.getX(), (double)next_wp.getY(), (global_triplet.previous_valid) ? "valid" : "invalid");
+
+ // XXX at this point we always want no loiter hold if a
+ // mission is active
+ _loiter_hold = false;
+
+ } else if (_control_mode.flag_armed) {
+
+ /* hold position, but only if armed, climb 20m in case this is engaged on ground level */
+
+ // XXX rework with smarter state machine
+
+ if (!_loiter_hold) {
+ _loiter_hold_lat = _global_pos.lat / 1e7f;
+ _loiter_hold_lon = _global_pos.lon / 1e7f;
+ _loiter_hold_alt = _global_pos.alt + 25.0f;
+ _loiter_hold = true;
+ }
+
+ altitude_error = _loiter_hold_alt - _global_pos.alt;
+
+ math::Vector2f loiter_hold_pos(_loiter_hold_lat, _loiter_hold_lon);
+
+ /* loiter around current position */
+ _l1_control.navigate_loiter(loiter_hold_pos, current_position, _parameters.loiter_hold_radius,
+ 1, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ /* climb with full throttle if the altitude error is bigger than 5 meters */
+ bool climb_out = (altitude_error > 3);
+
+ float min_pitch;
+
+ if (climb_out) {
+ min_pitch = math::radians(20.0f);
+
+ } else {
+ min_pitch = math::radians(_parameters.pitch_limit_min);
+ }
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _loiter_hold_alt, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ climb_out, min_pitch,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ if (climb_out) {
+ /* 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));
+ }
+ }
+
+ /* reset land state */
+ if (global_triplet.current.nav_cmd != NAV_CMD_LAND) {
+ land_noreturn = false;
+ }
+
+ if (was_circle_mode && !_l1_control.circle_mode()) {
+ /* just kicked out of loiter, reset roll integrals */
+ _att_sp.roll_reset_integral = true;
+ }
+
+ } else if (0/* easy mode enabled */) {
+
+ /** EASY FLIGHT **/
+
+ if (0/* switched from another mode to easy */) {
+ _seatbelt_hold_heading = _att.yaw;
+ }
+
+ if (0/* easy on and manual control yaw non-zero */) {
+ _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ }
+
+ /* climb out control */
+ bool climb_out = false;
+
+ /* user wants to climb out */
+ if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) {
+ climb_out = true;
+ }
+
+ /* if in seatbelt mode, set airspeed based on manual control */
+
+ // XXX check if ground speed undershoot should be applied here
+ float seatbelt_airspeed = _parameters.airspeed_min +
+ (_parameters.airspeed_max - _parameters.airspeed_min) *
+ _manual.throttle;
+
+ _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
+ seatbelt_airspeed,
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, _parameters.pitch_limit_min,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ _parameters.pitch_limit_min, _parameters.pitch_limit_max);
+
+ } else if (0/* seatbelt mode enabled */) {
+
+ /** SEATBELT FLIGHT **/
+
+ if (0/* switched from another mode to seatbelt */) {
+ _seatbelt_hold_heading = _att.yaw;
+ }
+
+ if (0/* seatbelt on and manual control yaw non-zero */) {
+ _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ }
+
+ /* if in seatbelt mode, set airspeed based on manual control */
+
+ // XXX check if ground speed undershoot should be applied here
+ float seatbelt_airspeed = _parameters.airspeed_min +
+ (_parameters.airspeed_max - _parameters.airspeed_min) *
+ _manual.throttle;
+
+ /* user switched off throttle */
+ if (_manual.throttle < 0.1f) {
+ throttle_max = 0.0f;
+ /* switch to pure pitch based altitude control, give up speed */
+ _tecs.set_speed_weight(0.0f);
+ }
+
+ /* climb out control */
+ bool climb_out = false;
+
+ /* user wants to climb out */
+ if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) {
+ climb_out = true;
+ }
+
+ _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
+ _att_sp.roll_body = _manual.roll;
+ _att_sp.yaw_body = _manual.yaw;
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
+ seatbelt_airspeed,
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ climb_out, _parameters.pitch_limit_min,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ _parameters.pitch_limit_min, _parameters.pitch_limit_max);
+
+ } else {
+
+ /** MANUAL FLIGHT **/
+
+ /* no flight mode applies, do not publish an attitude setpoint */
+ setpoint = false;
+ }
+
+ _att_sp.pitch_body = _tecs.get_pitch_demand();
+ _att_sp.thrust = math::min(_tecs.get_throttle_demand(), throttle_max);
+
+ return setpoint;
+}
+
+void
+FixedwingPositionControl::task_main()
+{
+
+ /* inform about start */
+ warnx("Initializing..");
+ fflush(stdout);
+
+ /*
+ * do subscriptions
+ */
+ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _global_set_triplet_sub = orb_subscribe(ORB_ID(vehicle_global_position_set_triplet));
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ _accel_sub = orb_subscribe(ORB_ID(sensor_accel));
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ _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));
+
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_control_mode_sub, 200);
+ /* rate limit position updates to 50 Hz */
+ orb_set_interval(_global_pos_sub, 20);
+
+ /* abort on a nonzero return value from the parameter init */
+ if (parameters_update()) {
+ /* parameter setup went wrong, abort */
+ warnx("aborting startup due to errors.");
+ _task_should_exit = true;
+ }
+
+ /* wakeup source(s) */
+ struct pollfd fds[2];
+
+ /* Setup of loop */
+ fds[0].fd = _params_sub;
+ fds[0].events = POLLIN;
+ fds[1].fd = _global_pos_sub;
+ fds[1].events = POLLIN;
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 500ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+
+ /* timed out - periodic check for _task_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* 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;
+ }
+
+ perf_begin(_loop_perf);
+
+ /* check vehicle status for changes to publication state */
+ vehicle_control_mode_poll();
+
+ /* only update parameters if they changed */
+ if (fds[0].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+
+ /* update parameters from storage */
+ parameters_update();
+ }
+
+ /* only run controller if position changed */
+ if (fds[1].revents & POLLIN) {
+
+
+ static uint64_t last_run = 0;
+ float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+ /* guard against too large deltaT's */
+ if (deltaT > 1.0f)
+ deltaT = 0.01f;
+
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+
+ // XXX add timestamp check
+ _global_pos_valid = true;
+
+ vehicle_attitude_poll();
+ vehicle_setpoint_poll();
+ vehicle_accel_poll();
+ vehicle_airspeed_poll();
+ // vehicle_baro_poll();
+
+ math::Vector2f ground_speed(_global_pos.vx, _global_pos.vy);
+ math::Vector2f current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
+
+ /*
+ * Attempt to control position, on success (= sensors present and not in manual mode),
+ * publish setpoint.
+ */
+ if (control_position(current_position, ground_speed, _global_triplet)) {
+ _att_sp.timestamp = hrt_absolute_time();
+
+ /* lazily publish the setpoint only once available */
+ if (_attitude_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _attitude_sp_pub, &_att_sp);
+
+ } else {
+ /* advertise and publish */
+ _attitude_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
+ }
+
+ float turn_distance = _l1_control.switch_distance(_global_triplet.current.turn_distance_xy);
+
+ /* lazily publish navigation capabilities */
+ if (turn_distance != _nav_capabilities.turn_distance && turn_distance > 0) {
+
+ /* set new turn distance */
+ _nav_capabilities.turn_distance = turn_distance;
+
+ if (_nav_capabilities_pub > 0) {
+ orb_publish(ORB_ID(navigation_capabilities), _nav_capabilities_pub, &_nav_capabilities);
+ } else {
+ _nav_capabilities_pub = orb_advertise(ORB_ID(navigation_capabilities), &_nav_capabilities);
+ }
+ }
+
+ }
+
+ }
+
+ perf_end(_loop_perf);
+ }
+
+ warnx("exiting.\n");
+
+ _control_task = -1;
+ _exit(0);
+}
+
+int
+FixedwingPositionControl::start()
+{
+ ASSERT(_control_task == -1);
+
+ /* start the task */
+ _control_task = task_spawn_cmd("fw_pos_control_l1",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 4048,
+ (main_t)&FixedwingPositionControl::task_main_trampoline,
+ nullptr);
+
+ if (_control_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int fw_pos_control_l1_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: fw_pos_control_l1 {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (l1_control::g_control != nullptr)
+ errx(1, "already running");
+
+ l1_control::g_control = new FixedwingPositionControl;
+
+ if (l1_control::g_control == nullptr)
+ errx(1, "alloc failed");
+
+ if (OK != l1_control::g_control->start()) {
+ delete l1_control::g_control;
+ l1_control::g_control = nullptr;
+ err(1, "start failed");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (l1_control::g_control == nullptr)
+ errx(1, "not running");
+
+ delete l1_control::g_control;
+ l1_control::g_control = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (l1_control::g_control) {
+ errx(0, "running");
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
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
new file mode 100644
index 000000000..31a9cdefa
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -0,0 +1,166 @@
+/****************************************************************************
+ *
+ * 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 fw_pos_control_l1_params.c
+ *
+ * Parameters defined by the L1 position control task
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Controller parameters, accessible via MAVLink
+ *
+ */
+
+/**
+ * L1 period
+ *
+ * This is the L1 distance and defines the tracking
+ * point ahead of the aircraft its following.
+ * A value of 25 meters works for most aircraft. Shorten
+ * slowly during tuning until response is sharp without oscillation.
+ *
+ * @min 1.0
+ * @max 100.0
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 25.0f);
+
+/**
+ * L1 damping
+ *
+ * Damping factor for L1 control.
+ *
+ * @min 0.6
+ * @max 0.9
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
+
+/**
+ * Default Loiter Radius
+ *
+ * This radius is used when no other loiter radius is set.
+ *
+ * @min 10.0
+ * @max 100.0
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_LOITER_R, 50.0f);
+
+/**
+ * Cruise throttle
+ *
+ * This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f);
+
+/**
+ * Negative pitch limit
+ *
+ * The minimum negative pitch the controller will output.
+ *
+ * @unit degrees
+ * @min -60.0
+ * @max 0.0
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
+
+/**
+ * Positive pitch limit
+ *
+ * The maximum positive pitch the controller will output.
+ *
+ * @unit degrees
+ * @min 0.0
+ * @max 60.0
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
+
+PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
+
+PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk
new file mode 100644
index 000000000..b00b9aa5a
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Fixedwing L1 position control application
+#
+
+MODULE_COMMAND = fw_pos_control_l1
+
+SRCS = fw_pos_control_l1_main.cpp \
+ fw_pos_control_l1_params.c
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index a80bf9cb8..d383146f9 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -48,22 +48,29 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_armed.h>
#include <poll.h>
#include <drivers/drv_gpio.h>
+#include <modules/px4iofirmware/protocol.h>
struct gpio_led_s {
struct work_s work;
int gpio_fd;
+ bool use_io;
int pin;
struct vehicle_status_s status;
int vehicle_status_sub;
+ struct actuator_armed_s armed;
+ int actuator_armed_sub;
bool led_state;
int counter;
};
static struct gpio_led_s gpio_led_data;
+static bool gpio_led_started = false;
__EXPORT int gpio_led_main(int argc, char *argv[]);
@@ -73,48 +80,128 @@ void gpio_led_cycle(FAR void *arg);
int gpio_led_main(int argc, char *argv[])
{
- int pin = GPIO_EXT_1;
+ if (argc < 2) {
+ errx(1, "usage: gpio_led {start|stop} [-p <1|2|a1|a2|r1|r2>]\n"
+ "\t-p\tUse pin:\n"
+ "\t\t1\tPX4FMU GPIO_EXT1 (default)\n"
+ "\t\t2\tPX4FMU GPIO_EXT2\n"
+ "\t\ta1\tPX4IO ACC1\n"
+ "\t\ta2\tPX4IO ACC2\n"
+ "\t\tr1\tPX4IO RELAY1\n"
+ "\t\tr2\tPX4IO RELAY2");
- if (argc > 1) {
- if (!strcmp(argv[1], "-p")) {
- if (!strcmp(argv[2], "1")) {
- pin = GPIO_EXT_1;
+ } else {
+
+ if (!strcmp(argv[1], "start")) {
+ if (gpio_led_started) {
+ errx(1, "already running");
+ }
+
+ bool use_io = false;
+ int pin = GPIO_EXT_1;
+
+ if (argc > 2) {
+ if (!strcmp(argv[2], "-p")) {
+ if (!strcmp(argv[3], "1")) {
+ use_io = false;
+ pin = GPIO_EXT_1;
+
+ } else if (!strcmp(argv[3], "2")) {
+ use_io = false;
+ pin = GPIO_EXT_2;
- } else if (!strcmp(argv[2], "2")) {
- pin = GPIO_EXT_2;
+ } else if (!strcmp(argv[3], "a1")) {
+ use_io = true;
+ pin = PX4IO_P_SETUP_RELAYS_ACC1;
+
+ } else if (!strcmp(argv[3], "a2")) {
+ use_io = true;
+ pin = PX4IO_P_SETUP_RELAYS_ACC2;
+
+ } else if (!strcmp(argv[3], "r1")) {
+ use_io = true;
+ pin = PX4IO_P_SETUP_RELAYS_POWER1;
+
+ } else if (!strcmp(argv[3], "r2")) {
+ use_io = true;
+ pin = PX4IO_P_SETUP_RELAYS_POWER2;
+
+ } else {
+ errx(1, "unsupported pin: %s", argv[3]);
+ }
+ }
+ }
+
+ memset(&gpio_led_data, 0, sizeof(gpio_led_data));
+ gpio_led_data.use_io = use_io;
+ gpio_led_data.pin = pin;
+ int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0);
+
+ if (ret != 0) {
+ errx(1, "failed to queue work: %d", ret);
} else {
- printf("[gpio_led] Unsupported pin: %s\n", argv[2]);
- exit(1);
+ gpio_led_started = true;
+ char pin_name[24];
+
+ if (use_io) {
+ if (pin & (PX4IO_P_SETUP_RELAYS_ACC1 | PX4IO_P_SETUP_RELAYS_ACC2)) {
+ sprintf(pin_name, "PX4IO ACC%i", (pin >> 3));
+
+ } else {
+ sprintf(pin_name, "PX4IO RELAY%i", pin);
+ }
+
+ } else {
+ sprintf(pin_name, "PX4FMU GPIO_EXT%i", pin);
+
+ }
+
+ warnx("start, using pin: %s", pin_name);
}
- }
- }
- memset(&gpio_led_data, 0, sizeof(gpio_led_data));
- gpio_led_data.pin = pin;
- int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0);
+ exit(0);
- if (ret != 0) {
- printf("[gpio_led] Failed to queue work: %d\n", ret);
- exit(1);
- }
- exit(0);
+ } else if (!strcmp(argv[1], "stop")) {
+ if (gpio_led_started) {
+ gpio_led_started = false;
+ warnx("stop");
+
+ } else {
+ errx(1, "not running");
+ }
+
+ } else {
+ errx(1, "unrecognized command '%s', only supporting 'start' or 'stop'", argv[1]);
+ }
+ }
}
void gpio_led_start(FAR void *arg)
{
FAR struct gpio_led_s *priv = (FAR struct gpio_led_s *)arg;
+ char *gpio_dev;
+
+ if (priv->use_io) {
+ gpio_dev = PX4IO_DEVICE_PATH;
+ } else {
+ gpio_dev = PX4FMU_DEVICE_PATH;
+ }
+
/* open GPIO device */
- priv->gpio_fd = open(GPIO_DEVICE_PATH, 0);
+ priv->gpio_fd = open(gpio_dev, 0);
if (priv->gpio_fd < 0) {
- printf("[gpio_led] GPIO: open fail\n");
+ // TODO find way to print errors
+ //printf("gpio_led: GPIO device \"%s\" open fail\n", gpio_dev);
+ gpio_led_started = false;
return;
}
/* configure GPIO pin */
+ /* px4fmu only, px4io doesn't support GPIO_SET_OUTPUT and will ignore */
ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, priv->pin);
/* subscribe to vehicle status topic */
@@ -125,11 +212,11 @@ void gpio_led_start(FAR void *arg)
int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0);
if (ret != 0) {
- printf("[gpio_led] Failed to queue work: %d\n", ret);
+ // TODO find way to print errors
+ //printf("gpio_led: failed to queue work: %d\n", ret);
+ gpio_led_started = false;
return;
}
-
- printf("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin);
}
void gpio_led_cycle(FAR void *arg)
@@ -143,10 +230,15 @@ void gpio_led_cycle(FAR void *arg)
if (status_updated)
orb_copy(ORB_ID(vehicle_status), priv->vehicle_status_sub, &priv->status);
+ orb_check(priv->vehicle_status_sub, &status_updated);
+
+ if (status_updated)
+ orb_copy(ORB_ID(actuator_armed), priv->actuator_armed_sub, &priv->armed);
+
/* select pattern for current status */
int pattern = 0;
- if (priv->status.flag_system_armed) {
+ if (priv->armed.armed) {
if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
pattern = 0x3f; // ****** solid (armed)
@@ -155,11 +247,10 @@ void gpio_led_cycle(FAR void *arg)
}
} else {
- if (priv->status.state_machine == SYSTEM_STATE_PREFLIGHT) {
+ if (priv->armed.ready_to_arm) {
pattern = 0x00; // ______ off (disarmed, preflight check)
- } else if (priv->status.state_machine == SYSTEM_STATE_STANDBY &&
- priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
+ } else if (priv->armed.ready_to_arm && priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
pattern = 0x38; // ***___ slow blink (disarmed, ready)
} else {
@@ -175,7 +266,6 @@ void gpio_led_cycle(FAR void *arg)
if (led_state_new) {
ioctl(priv->gpio_fd, GPIO_SET, priv->pin);
-
} else {
ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin);
}
@@ -186,6 +276,12 @@ void gpio_led_cycle(FAR void *arg)
if (priv->counter > 5)
priv->counter = 0;
- /* repeat cycle at 5 Hz*/
- work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
+ /* repeat cycle at 5 Hz */
+ if (gpio_led_started) {
+ work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
+
+ } else {
+ /* switch off LED on stop */
+ ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin);
+ }
}
diff --git a/src/modules/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h b/src/modules/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h
deleted file mode 100644
index 8f39acd9d..000000000
--- a/src/modules/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h
+++ /dev/null
@@ -1,264 +0,0 @@
-/**************************************************************************//**
- * @file ARMCM3.h
- * @brief CMSIS Core Peripheral Access Layer Header File for
- * ARMCM3 Device Series
- * @version V1.07
- * @date 30. January 2012
- *
- * @note
- * Copyright (C) 2012 ARM Limited. All rights reserved.
- *
- * @par
- * ARM Limited (ARM) is supplying this software for use with Cortex-M
- * processor based microcontrollers. This file can be freely distributed
- * within development tools that are supporting such ARM based processors.
- *
- * @par
- * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
- * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
- * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
- * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
- *
- ******************************************************************************/
-
-#ifndef ARMCM3_H
-#define ARMCM3_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-
-/* ------------------------- Interrupt Number Definition ------------------------ */
-
-typedef enum IRQn
-{
-/* ------------------- Cortex-M3 Processor Exceptions Numbers ------------------- */
- NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< 3 HardFault Interrupt */
- MemoryManagement_IRQn = -12, /*!< 4 Memory Management Interrupt */
- BusFault_IRQn = -11, /*!< 5 Bus Fault Interrupt */
- UsageFault_IRQn = -10, /*!< 6 Usage Fault Interrupt */
- SVCall_IRQn = -5, /*!< 11 SV Call Interrupt */
- DebugMonitor_IRQn = -4, /*!< 12 Debug Monitor Interrupt */
- PendSV_IRQn = -2, /*!< 14 Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< 15 System Tick Interrupt */
-
-/* ---------------------- ARMCM3 Specific Interrupt Numbers --------------------- */
- WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */
- RTC_IRQn = 1, /*!< Real Time Clock Interrupt */
- TIM0_IRQn = 2, /*!< Timer0 / Timer1 Interrupt */
- TIM2_IRQn = 3, /*!< Timer2 / Timer3 Interrupt */
- MCIA_IRQn = 4, /*!< MCIa Interrupt */
- MCIB_IRQn = 5, /*!< MCIb Interrupt */
- UART0_IRQn = 6, /*!< UART0 Interrupt */
- UART1_IRQn = 7, /*!< UART1 Interrupt */
- UART2_IRQn = 8, /*!< UART2 Interrupt */
- UART4_IRQn = 9, /*!< UART4 Interrupt */
- AACI_IRQn = 10, /*!< AACI / AC97 Interrupt */
- CLCD_IRQn = 11, /*!< CLCD Combined Interrupt */
- ENET_IRQn = 12, /*!< Ethernet Interrupt */
- USBDC_IRQn = 13, /*!< USB Device Interrupt */
- USBHC_IRQn = 14, /*!< USB Host Controller Interrupt */
- CHLCD_IRQn = 15, /*!< Character LCD Interrupt */
- FLEXRAY_IRQn = 16, /*!< Flexray Interrupt */
- CAN_IRQn = 17, /*!< CAN Interrupt */
- LIN_IRQn = 18, /*!< LIN Interrupt */
- I2C_IRQn = 19, /*!< I2C ADC/DAC Interrupt */
- CPU_CLCD_IRQn = 28, /*!< CPU CLCD Combined Interrupt */
- UART3_IRQn = 30, /*!< UART3 Interrupt */
- SPI_IRQn = 31, /*!< SPI Touchscreen Interrupt */
-} IRQn_Type;
-
-
-/* ================================================================================ */
-/* ================ Processor and Core Peripheral Section ================ */
-/* ================================================================================ */
-
-/* -------- Configuration of the Cortex-M4 Processor and Core Peripherals ------- */
-#define __CM3_REV 0x0201 /*!< Core revision r2p1 */
-#define __MPU_PRESENT 1 /*!< MPU present or not */
-#define __NVIC_PRIO_BITS 3 /*!< Number of Bits used for Priority Levels */
-#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
-
-#include <core_cm3.h> /* Processor and core peripherals */
-/* NuttX */
-//#include "system_ARMCM3.h" /* System Header */
-
-
-/* ================================================================================ */
-/* ================ Device Specific Peripheral Section ================ */
-/* ================================================================================ */
-
-/* ------------------- Start of section using anonymous unions ------------------ */
-#if defined(__CC_ARM)
- #pragma push
- #pragma anon_unions
-#elif defined(__ICCARM__)
- #pragma language=extended
-#elif defined(__GNUC__)
- /* anonymous unions are enabled by default */
-#elif defined(__TMS470__)
-/* anonymous unions are enabled by default */
-#elif defined(__TASKING__)
- #pragma warning 586
-#else
- #warning Not supported compiler type
-#endif
-
-
-
-/* ================================================================================ */
-/* ================ CPU FPGA System (CPU_SYS) ================ */
-/* ================================================================================ */
-typedef struct
-{
- __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
- __IO uint32_t MEMCFG; /* Offset: 0x004 (R/W) Remap and Alias Memory Control */
- __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
- __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
- __I uint32_t TS; /* Offset: 0x010 (R/ ) Touchscreen Register */
- __IO uint32_t CTRL1; /* Offset: 0x014 (R/W) Misc Control Functions */
- uint32_t RESERVED0[2];
- __IO uint32_t CLKCFG; /* Offset: 0x020 (R/W) System Clock Configuration */
- __IO uint32_t WSCFG; /* Offset: 0x024 (R/W) Flash Waitstate Configuration */
- __IO uint32_t CPUCFG; /* Offset: 0x028 (R/W) Processor Configuration */
- uint32_t RESERVED1[3];
- __IO uint32_t BASE; /* Offset: 0x038 (R/W) ROM Table base Address */
- __IO uint32_t ID2; /* Offset: 0x03C (R/W) Secondary Identification Register */
-} ARM_CPU_SYS_TypeDef;
-
-
-/* ================================================================================ */
-/* ================ DUT FPGA System (DUT_SYS) ================ */
-/* ================================================================================ */
-typedef struct
-{
- __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
- __IO uint32_t PERCFG; /* Offset: 0x004 (R/W) Peripheral Control Signals */
- __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
- __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
- __IO uint32_t SEG7; /* Offset: 0x010 (R/W) 7-segment LED Output States */
- __I uint32_t CNT25MHz; /* Offset: 0x014 (R/ ) Freerunning counter incrementing at 25MHz */
- __I uint32_t CNT100Hz; /* Offset: 0x018 (R/ ) Freerunning counter incrementing at 100Hz */
-} ARM_DUT_SYS_TypeDef;
-
-
-/* ================================================================================ */
-/* ================ Timer (TIM) ================ */
-/* ================================================================================ */
-typedef struct
-{
- __IO uint32_t Timer1Load; /* Offset: 0x000 (R/W) Timer 1 Load */
- __I uint32_t Timer1Value; /* Offset: 0x004 (R/ ) Timer 1 Counter Current Value */
- __IO uint32_t Timer1Control; /* Offset: 0x008 (R/W) Timer 1 Control */
- __O uint32_t Timer1IntClr; /* Offset: 0x00C ( /W) Timer 1 Interrupt Clear */
- __I uint32_t Timer1RIS; /* Offset: 0x010 (R/ ) Timer 1 Raw Interrupt Status */
- __I uint32_t Timer1MIS; /* Offset: 0x014 (R/ ) Timer 1 Masked Interrupt Status */
- __IO uint32_t Timer1BGLoad; /* Offset: 0x018 (R/W) Background Load Register */
- uint32_t RESERVED0[1];
- __IO uint32_t Timer2Load; /* Offset: 0x020 (R/W) Timer 2 Load */
- __I uint32_t Timer2Value; /* Offset: 0x024 (R/ ) Timer 2 Counter Current Value */
- __IO uint32_t Timer2Control; /* Offset: 0x028 (R/W) Timer 2 Control */
- __O uint32_t Timer2IntClr; /* Offset: 0x02C ( /W) Timer 2 Interrupt Clear */
- __I uint32_t Timer2RIS; /* Offset: 0x030 (R/ ) Timer 2 Raw Interrupt Status */
- __I uint32_t Timer2MIS; /* Offset: 0x034 (R/ ) Timer 2 Masked Interrupt Status */
- __IO uint32_t Timer2BGLoad; /* Offset: 0x038 (R/W) Background Load Register */
-} ARM_TIM_TypeDef;
-
-
-/* ================================================================================ */
-/* ============== Universal Asyncronous Receiver / Transmitter (UART) ============= */
-/* ================================================================================ */
-typedef struct
-{
- __IO uint32_t DR; /* Offset: 0x000 (R/W) Data */
- union {
- __I uint32_t RSR; /* Offset: 0x000 (R/ ) Receive Status */
- __O uint32_t ECR; /* Offset: 0x000 ( /W) Error Clear */
- };
- uint32_t RESERVED0[4];
- __IO uint32_t FR; /* Offset: 0x018 (R/W) Flags */
- uint32_t RESERVED1[1];
- __IO uint32_t ILPR; /* Offset: 0x020 (R/W) IrDA Low-power Counter */
- __IO uint32_t IBRD; /* Offset: 0x024 (R/W) Interger Baud Rate */
- __IO uint32_t FBRD; /* Offset: 0x028 (R/W) Fractional Baud Rate */
- __IO uint32_t LCR_H; /* Offset: 0x02C (R/W) Line Control */
- __IO uint32_t CR; /* Offset: 0x030 (R/W) Control */
- __IO uint32_t IFLS; /* Offset: 0x034 (R/W) Interrupt FIFO Level Select */
- __IO uint32_t IMSC; /* Offset: 0x038 (R/W) Interrupt Mask Set / Clear */
- __IO uint32_t RIS; /* Offset: 0x03C (R/W) Raw Interrupt Status */
- __IO uint32_t MIS; /* Offset: 0x040 (R/W) Masked Interrupt Status */
- __O uint32_t ICR; /* Offset: 0x044 ( /W) Interrupt Clear */
- __IO uint32_t DMACR; /* Offset: 0x048 (R/W) DMA Control */
-} ARM_UART_TypeDef;
-
-
-/* -------------------- End of section using anonymous unions ------------------- */
-#if defined(__CC_ARM)
- #pragma pop
-#elif defined(__ICCARM__)
- /* leave anonymous unions enabled */
-#elif defined(__GNUC__)
- /* anonymous unions are enabled by default */
-#elif defined(__TMS470__)
- /* anonymous unions are enabled by default */
-#elif defined(__TASKING__)
- #pragma warning restore
-#else
- #warning Not supported compiler type
-#endif
-
-
-
-
-/* ================================================================================ */
-/* ================ Peripheral memory map ================ */
-/* ================================================================================ */
-/* -------------------------- CPU FPGA memory map ------------------------------- */
-#define ARM_FLASH_BASE (0x00000000UL)
-#define ARM_RAM_BASE (0x20000000UL)
-#define ARM_RAM_FPGA_BASE (0x1EFF0000UL)
-#define ARM_CPU_CFG_BASE (0xDFFF0000UL)
-
-#define ARM_CPU_SYS_BASE (ARM_CPU_CFG_BASE + 0x00000)
-#define ARM_UART3_BASE (ARM_CPU_CFG_BASE + 0x05000)
-
-/* -------------------------- DUT FPGA memory map ------------------------------- */
-#define ARM_APB_BASE (0x40000000UL)
-#define ARM_AHB_BASE (0x4FF00000UL)
-#define ARM_DMC_BASE (0x60000000UL)
-#define ARM_SMC_BASE (0xA0000000UL)
-
-#define ARM_TIM0_BASE (ARM_APB_BASE + 0x02000)
-#define ARM_TIM2_BASE (ARM_APB_BASE + 0x03000)
-#define ARM_DUT_SYS_BASE (ARM_APB_BASE + 0x04000)
-#define ARM_UART0_BASE (ARM_APB_BASE + 0x06000)
-#define ARM_UART1_BASE (ARM_APB_BASE + 0x07000)
-#define ARM_UART2_BASE (ARM_APB_BASE + 0x08000)
-#define ARM_UART4_BASE (ARM_APB_BASE + 0x09000)
-
-
-/* ================================================================================ */
-/* ================ Peripheral declaration ================ */
-/* ================================================================================ */
-/* -------------------------- CPU FPGA Peripherals ------------------------------ */
-#define ARM_CPU_SYS ((ARM_CPU_SYS_TypeDef *) ARM_CPU_SYS_BASE)
-#define ARM_UART3 (( ARM_UART_TypeDef *) ARM_UART3_BASE)
-
-/* -------------------------- DUT FPGA Peripherals ------------------------------ */
-#define ARM_DUT_SYS ((ARM_DUT_SYS_TypeDef *) ARM_DUT_SYS_BASE)
-#define ARM_TIM0 (( ARM_TIM_TypeDef *) ARM_TIM0_BASE)
-#define ARM_TIM2 (( ARM_TIM_TypeDef *) ARM_TIM2_BASE)
-#define ARM_UART0 (( ARM_UART_TypeDef *) ARM_UART0_BASE)
-#define ARM_UART1 (( ARM_UART_TypeDef *) ARM_UART1_BASE)
-#define ARM_UART2 (( ARM_UART_TypeDef *) ARM_UART2_BASE)
-#define ARM_UART4 (( ARM_UART_TypeDef *) ARM_UART4_BASE)
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* ARMCM3_H */
diff --git a/src/modules/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h b/src/modules/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h
deleted file mode 100644
index 181b7e433..000000000
--- a/src/modules/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h
+++ /dev/null
@@ -1,265 +0,0 @@
-/**************************************************************************//**
- * @file ARMCM4.h
- * @brief CMSIS Core Peripheral Access Layer Header File for
- * ARMCM4 Device Series
- * @version V1.07
- * @date 30. January 2012
- *
- * @note
- * Copyright (C) 2012 ARM Limited. All rights reserved.
- *
- * @par
- * ARM Limited (ARM) is supplying this software for use with Cortex-M
- * processor based microcontrollers. This file can be freely distributed
- * within development tools that are supporting such ARM based processors.
- *
- * @par
- * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
- * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
- * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
- * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
- *
- ******************************************************************************/
-
-#ifndef ARMCM4_H
-#define ARMCM4_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-
-/* ------------------------- Interrupt Number Definition ------------------------ */
-
-typedef enum IRQn
-{
-/* ------------------- Cortex-M4 Processor Exceptions Numbers ------------------- */
- NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */
- HardFault_IRQn = -13, /*!< 3 HardFault Interrupt */
- MemoryManagement_IRQn = -12, /*!< 4 Memory Management Interrupt */
- BusFault_IRQn = -11, /*!< 5 Bus Fault Interrupt */
- UsageFault_IRQn = -10, /*!< 6 Usage Fault Interrupt */
- SVCall_IRQn = -5, /*!< 11 SV Call Interrupt */
- DebugMonitor_IRQn = -4, /*!< 12 Debug Monitor Interrupt */
- PendSV_IRQn = -2, /*!< 14 Pend SV Interrupt */
- SysTick_IRQn = -1, /*!< 15 System Tick Interrupt */
-
-/* ---------------------- ARMCM4 Specific Interrupt Numbers --------------------- */
- WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */
- RTC_IRQn = 1, /*!< Real Time Clock Interrupt */
- TIM0_IRQn = 2, /*!< Timer0 / Timer1 Interrupt */
- TIM2_IRQn = 3, /*!< Timer2 / Timer3 Interrupt */
- MCIA_IRQn = 4, /*!< MCIa Interrupt */
- MCIB_IRQn = 5, /*!< MCIb Interrupt */
- UART0_IRQn = 6, /*!< UART0 Interrupt */
- UART1_IRQn = 7, /*!< UART1 Interrupt */
- UART2_IRQn = 8, /*!< UART2 Interrupt */
- UART4_IRQn = 9, /*!< UART4 Interrupt */
- AACI_IRQn = 10, /*!< AACI / AC97 Interrupt */
- CLCD_IRQn = 11, /*!< CLCD Combined Interrupt */
- ENET_IRQn = 12, /*!< Ethernet Interrupt */
- USBDC_IRQn = 13, /*!< USB Device Interrupt */
- USBHC_IRQn = 14, /*!< USB Host Controller Interrupt */
- CHLCD_IRQn = 15, /*!< Character LCD Interrupt */
- FLEXRAY_IRQn = 16, /*!< Flexray Interrupt */
- CAN_IRQn = 17, /*!< CAN Interrupt */
- LIN_IRQn = 18, /*!< LIN Interrupt */
- I2C_IRQn = 19, /*!< I2C ADC/DAC Interrupt */
- CPU_CLCD_IRQn = 28, /*!< CPU CLCD Combined Interrupt */
- UART3_IRQn = 30, /*!< UART3 Interrupt */
- SPI_IRQn = 31, /*!< SPI Touchscreen Interrupt */
-} IRQn_Type;
-
-
-/* ================================================================================ */
-/* ================ Processor and Core Peripheral Section ================ */
-/* ================================================================================ */
-
-/* -------- Configuration of the Cortex-M4 Processor and Core Peripherals ------- */
-#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
-#define __MPU_PRESENT 1 /*!< MPU present or not */
-#define __NVIC_PRIO_BITS 3 /*!< Number of Bits used for Priority Levels */
-#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
-#define __FPU_PRESENT 1 /*!< FPU present or not */
-
-#include <core_cm4.h> /* Processor and core peripherals */
-/* NuttX */
-//#include "system_ARMCM4.h" /* System Header */
-
-
-/* ================================================================================ */
-/* ================ Device Specific Peripheral Section ================ */
-/* ================================================================================ */
-
-/* ------------------- Start of section using anonymous unions ------------------ */
-#if defined(__CC_ARM)
- #pragma push
- #pragma anon_unions
-#elif defined(__ICCARM__)
- #pragma language=extended
-#elif defined(__GNUC__)
- /* anonymous unions are enabled by default */
-#elif defined(__TMS470__)
-/* anonymous unions are enabled by default */
-#elif defined(__TASKING__)
- #pragma warning 586
-#else
- #warning Not supported compiler type
-#endif
-
-
-
-/* ================================================================================ */
-/* ================ CPU FPGA System (CPU_SYS) ================ */
-/* ================================================================================ */
-typedef struct
-{
- __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
- __IO uint32_t MEMCFG; /* Offset: 0x004 (R/W) Remap and Alias Memory Control */
- __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
- __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
- __I uint32_t TS; /* Offset: 0x010 (R/ ) Touchscreen Register */
- __IO uint32_t CTRL1; /* Offset: 0x014 (R/W) Misc Control Functions */
- uint32_t RESERVED0[2];
- __IO uint32_t CLKCFG; /* Offset: 0x020 (R/W) System Clock Configuration */
- __IO uint32_t WSCFG; /* Offset: 0x024 (R/W) Flash Waitstate Configuration */
- __IO uint32_t CPUCFG; /* Offset: 0x028 (R/W) Processor Configuration */
- uint32_t RESERVED1[3];
- __IO uint32_t BASE; /* Offset: 0x038 (R/W) ROM Table base Address */
- __IO uint32_t ID2; /* Offset: 0x03C (R/W) Secondary Identification Register */
-} ARM_CPU_SYS_TypeDef;
-
-
-/* ================================================================================ */
-/* ================ DUT FPGA System (DUT_SYS) ================ */
-/* ================================================================================ */
-typedef struct
-{
- __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
- __IO uint32_t PERCFG; /* Offset: 0x004 (R/W) Peripheral Control Signals */
- __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
- __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
- __IO uint32_t SEG7; /* Offset: 0x010 (R/W) 7-segment LED Output States */
- __I uint32_t CNT25MHz; /* Offset: 0x014 (R/ ) Freerunning counter incrementing at 25MHz */
- __I uint32_t CNT100Hz; /* Offset: 0x018 (R/ ) Freerunning counter incrementing at 100Hz */
-} ARM_DUT_SYS_TypeDef;
-
-
-/* ================================================================================ */
-/* ================ Timer (TIM) ================ */
-/* ================================================================================ */
-typedef struct
-{
- __IO uint32_t Timer1Load; /* Offset: 0x000 (R/W) Timer 1 Load */
- __I uint32_t Timer1Value; /* Offset: 0x004 (R/ ) Timer 1 Counter Current Value */
- __IO uint32_t Timer1Control; /* Offset: 0x008 (R/W) Timer 1 Control */
- __O uint32_t Timer1IntClr; /* Offset: 0x00C ( /W) Timer 1 Interrupt Clear */
- __I uint32_t Timer1RIS; /* Offset: 0x010 (R/ ) Timer 1 Raw Interrupt Status */
- __I uint32_t Timer1MIS; /* Offset: 0x014 (R/ ) Timer 1 Masked Interrupt Status */
- __IO uint32_t Timer1BGLoad; /* Offset: 0x018 (R/W) Background Load Register */
- uint32_t RESERVED0[1];
- __IO uint32_t Timer2Load; /* Offset: 0x020 (R/W) Timer 2 Load */
- __I uint32_t Timer2Value; /* Offset: 0x024 (R/ ) Timer 2 Counter Current Value */
- __IO uint32_t Timer2Control; /* Offset: 0x028 (R/W) Timer 2 Control */
- __O uint32_t Timer2IntClr; /* Offset: 0x02C ( /W) Timer 2 Interrupt Clear */
- __I uint32_t Timer2RIS; /* Offset: 0x030 (R/ ) Timer 2 Raw Interrupt Status */
- __I uint32_t Timer2MIS; /* Offset: 0x034 (R/ ) Timer 2 Masked Interrupt Status */
- __IO uint32_t Timer2BGLoad; /* Offset: 0x038 (R/W) Background Load Register */
-} ARM_TIM_TypeDef;
-
-
-/* ================================================================================ */
-/* ============== Universal Asyncronous Receiver / Transmitter (UART) ============= */
-/* ================================================================================ */
-typedef struct
-{
- __IO uint32_t DR; /* Offset: 0x000 (R/W) Data */
- union {
- __I uint32_t RSR; /* Offset: 0x000 (R/ ) Receive Status */
- __O uint32_t ECR; /* Offset: 0x000 ( /W) Error Clear */
- };
- uint32_t RESERVED0[4];
- __IO uint32_t FR; /* Offset: 0x018 (R/W) Flags */
- uint32_t RESERVED1[1];
- __IO uint32_t ILPR; /* Offset: 0x020 (R/W) IrDA Low-power Counter */
- __IO uint32_t IBRD; /* Offset: 0x024 (R/W) Interger Baud Rate */
- __IO uint32_t FBRD; /* Offset: 0x028 (R/W) Fractional Baud Rate */
- __IO uint32_t LCR_H; /* Offset: 0x02C (R/W) Line Control */
- __IO uint32_t CR; /* Offset: 0x030 (R/W) Control */
- __IO uint32_t IFLS; /* Offset: 0x034 (R/W) Interrupt FIFO Level Select */
- __IO uint32_t IMSC; /* Offset: 0x038 (R/W) Interrupt Mask Set / Clear */
- __IO uint32_t RIS; /* Offset: 0x03C (R/W) Raw Interrupt Status */
- __IO uint32_t MIS; /* Offset: 0x040 (R/W) Masked Interrupt Status */
- __O uint32_t ICR; /* Offset: 0x044 ( /W) Interrupt Clear */
- __IO uint32_t DMACR; /* Offset: 0x048 (R/W) DMA Control */
-} ARM_UART_TypeDef;
-
-
-/* -------------------- End of section using anonymous unions ------------------- */
-#if defined(__CC_ARM)
- #pragma pop
-#elif defined(__ICCARM__)
- /* leave anonymous unions enabled */
-#elif defined(__GNUC__)
- /* anonymous unions are enabled by default */
-#elif defined(__TMS470__)
- /* anonymous unions are enabled by default */
-#elif defined(__TASKING__)
- #pragma warning restore
-#else
- #warning Not supported compiler type
-#endif
-
-
-
-
-/* ================================================================================ */
-/* ================ Peripheral memory map ================ */
-/* ================================================================================ */
-/* -------------------------- CPU FPGA memory map ------------------------------- */
-#define ARM_FLASH_BASE (0x00000000UL)
-#define ARM_RAM_BASE (0x20000000UL)
-#define ARM_RAM_FPGA_BASE (0x1EFF0000UL)
-#define ARM_CPU_CFG_BASE (0xDFFF0000UL)
-
-#define ARM_CPU_SYS_BASE (ARM_CPU_CFG_BASE + 0x00000)
-#define ARM_UART3_BASE (ARM_CPU_CFG_BASE + 0x05000)
-
-/* -------------------------- DUT FPGA memory map ------------------------------- */
-#define ARM_APB_BASE (0x40000000UL)
-#define ARM_AHB_BASE (0x4FF00000UL)
-#define ARM_DMC_BASE (0x60000000UL)
-#define ARM_SMC_BASE (0xA0000000UL)
-
-#define ARM_TIM0_BASE (ARM_APB_BASE + 0x02000)
-#define ARM_TIM2_BASE (ARM_APB_BASE + 0x03000)
-#define ARM_DUT_SYS_BASE (ARM_APB_BASE + 0x04000)
-#define ARM_UART0_BASE (ARM_APB_BASE + 0x06000)
-#define ARM_UART1_BASE (ARM_APB_BASE + 0x07000)
-#define ARM_UART2_BASE (ARM_APB_BASE + 0x08000)
-#define ARM_UART4_BASE (ARM_APB_BASE + 0x09000)
-
-
-/* ================================================================================ */
-/* ================ Peripheral declaration ================ */
-/* ================================================================================ */
-/* -------------------------- CPU FPGA Peripherals ------------------------------ */
-#define ARM_CPU_SYS ((ARM_CPU_SYS_TypeDef *) ARM_CPU_SYS_BASE)
-#define ARM_UART3 (( ARM_UART_TypeDef *) ARM_UART3_BASE)
-
-/* -------------------------- DUT FPGA Peripherals ------------------------------ */
-#define ARM_DUT_SYS ((ARM_DUT_SYS_TypeDef *) ARM_DUT_SYS_BASE)
-#define ARM_TIM0 (( ARM_TIM_TypeDef *) ARM_TIM0_BASE)
-#define ARM_TIM2 (( ARM_TIM_TypeDef *) ARM_TIM2_BASE)
-#define ARM_UART0 (( ARM_UART_TypeDef *) ARM_UART0_BASE)
-#define ARM_UART1 (( ARM_UART_TypeDef *) ARM_UART1_BASE)
-#define ARM_UART2 (( ARM_UART_TypeDef *) ARM_UART2_BASE)
-#define ARM_UART4 (( ARM_UART_TypeDef *) ARM_UART4_BASE)
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* ARMCM4_H */
diff --git a/src/modules/mathlib/CMSIS/Include/arm_common_tables.h b/src/modules/mathlib/CMSIS/Include/arm_common_tables.h
deleted file mode 100644
index 9c37ab4e5..000000000
--- a/src/modules/mathlib/CMSIS/Include/arm_common_tables.h
+++ /dev/null
@@ -1,93 +0,0 @@
-/* ----------------------------------------------------------------------
-* Copyright (C) 2010-2013 ARM Limited. All rights reserved.
-*
-* $Date: 17. January 2013
-* $Revision: V1.4.1
-*
-* Project: CMSIS DSP Library
-* Title: arm_common_tables.h
-*
-* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions
-*
-* Target Processor: Cortex-M4/Cortex-M3
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-* - Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* - 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.
-* - Neither the name of ARM LIMITED 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.
-* -------------------------------------------------------------------- */
-
-#ifndef _ARM_COMMON_TABLES_H
-#define _ARM_COMMON_TABLES_H
-
-#include "arm_math.h"
-
-extern const uint16_t armBitRevTable[1024];
-extern const q15_t armRecipTableQ15[64];
-extern const q31_t armRecipTableQ31[64];
-extern const q31_t realCoefAQ31[1024];
-extern const q31_t realCoefBQ31[1024];
-extern const float32_t twiddleCoef_16[32];
-extern const float32_t twiddleCoef_32[64];
-extern const float32_t twiddleCoef_64[128];
-extern const float32_t twiddleCoef_128[256];
-extern const float32_t twiddleCoef_256[512];
-extern const float32_t twiddleCoef_512[1024];
-extern const float32_t twiddleCoef_1024[2048];
-extern const float32_t twiddleCoef_2048[4096];
-extern const float32_t twiddleCoef_4096[8192];
-#define twiddleCoef twiddleCoef_4096
-extern const q31_t twiddleCoefQ31[6144];
-extern const q15_t twiddleCoefQ15[6144];
-extern const float32_t twiddleCoef_rfft_32[32];
-extern const float32_t twiddleCoef_rfft_64[64];
-extern const float32_t twiddleCoef_rfft_128[128];
-extern const float32_t twiddleCoef_rfft_256[256];
-extern const float32_t twiddleCoef_rfft_512[512];
-extern const float32_t twiddleCoef_rfft_1024[1024];
-extern const float32_t twiddleCoef_rfft_2048[2048];
-extern const float32_t twiddleCoef_rfft_4096[4096];
-
-
-#define ARMBITREVINDEXTABLE__16_TABLE_LENGTH ((uint16_t)20 )
-#define ARMBITREVINDEXTABLE__32_TABLE_LENGTH ((uint16_t)48 )
-#define ARMBITREVINDEXTABLE__64_TABLE_LENGTH ((uint16_t)56 )
-#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208 )
-#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440 )
-#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448 )
-#define ARMBITREVINDEXTABLE1024_TABLE_LENGTH ((uint16_t)1800)
-#define ARMBITREVINDEXTABLE2048_TABLE_LENGTH ((uint16_t)3808)
-#define ARMBITREVINDEXTABLE4096_TABLE_LENGTH ((uint16_t)4032)
-
-extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE__16_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE__32_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE__64_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE1024_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE2048_TABLE_LENGTH];
-extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE4096_TABLE_LENGTH];
-
-#endif /* ARM_COMMON_TABLES_H */
diff --git a/src/modules/mathlib/CMSIS/Include/arm_const_structs.h b/src/modules/mathlib/CMSIS/Include/arm_const_structs.h
deleted file mode 100644
index 406f737dc..000000000
--- a/src/modules/mathlib/CMSIS/Include/arm_const_structs.h
+++ /dev/null
@@ -1,85 +0,0 @@
-/* ----------------------------------------------------------------------
-* Copyright (C) 2010-2013 ARM Limited. All rights reserved.
-*
-* $Date: 17. January 2013
-* $Revision: V1.4.1
-*
-* Project: CMSIS DSP Library
-* Title: arm_const_structs.h
-*
-* Description: This file has constant structs that are initialized for
-* user convenience. For example, some can be given as
-* arguments to the arm_cfft_f32() function.
-*
-* Target Processor: Cortex-M4/Cortex-M3
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-* - Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* - 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.
-* - Neither the name of ARM LIMITED 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.
-* -------------------------------------------------------------------- */
-
-#ifndef _ARM_CONST_STRUCTS_H
-#define _ARM_CONST_STRUCTS_H
-
-#include "arm_math.h"
-#include "arm_common_tables.h"
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len16 = {
- 16, twiddleCoef_16, armBitRevIndexTable16, ARMBITREVINDEXTABLE__16_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len32 = {
- 32, twiddleCoef_32, armBitRevIndexTable32, ARMBITREVINDEXTABLE__32_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len64 = {
- 64, twiddleCoef_64, armBitRevIndexTable64, ARMBITREVINDEXTABLE__64_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len128 = {
- 128, twiddleCoef_128, armBitRevIndexTable128, ARMBITREVINDEXTABLE_128_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len256 = {
- 256, twiddleCoef_256, armBitRevIndexTable256, ARMBITREVINDEXTABLE_256_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len512 = {
- 512, twiddleCoef_512, armBitRevIndexTable512, ARMBITREVINDEXTABLE_512_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024 = {
- 1024, twiddleCoef_1024, armBitRevIndexTable1024, ARMBITREVINDEXTABLE1024_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048 = {
- 2048, twiddleCoef_2048, armBitRevIndexTable2048, ARMBITREVINDEXTABLE2048_TABLE_LENGTH
- };
-
- const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096 = {
- 4096, twiddleCoef_4096, armBitRevIndexTable4096, ARMBITREVINDEXTABLE4096_TABLE_LENGTH
- };
-
-#endif
diff --git a/src/modules/mathlib/CMSIS/Include/arm_math.h b/src/modules/mathlib/CMSIS/Include/arm_math.h
deleted file mode 100644
index 6f66f9ee3..000000000
--- a/src/modules/mathlib/CMSIS/Include/arm_math.h
+++ /dev/null
@@ -1,7318 +0,0 @@
-/* ----------------------------------------------------------------------
-* Copyright (C) 2010-2013 ARM Limited. All rights reserved.
-*
-* $Date: 17. January 2013
-* $Revision: V1.4.1
-*
-* Project: CMSIS DSP Library
-* Title: arm_math.h
-*
-* Description: Public header file for CMSIS DSP Library
-*
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-* - Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* - 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.
-* - Neither the name of ARM LIMITED 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.
- * -------------------------------------------------------------------- */
-
-/**
- \mainpage CMSIS DSP Software Library
- *
- * <b>Introduction</b>
- *
- * This user manual describes the CMSIS DSP software library,
- * a suite of common signal processing functions for use on Cortex-M processor based devices.
- *
- * The library is divided into a number of functions each covering a specific category:
- * - Basic math functions
- * - Fast math functions
- * - Complex math functions
- * - Filters
- * - Matrix functions
- * - Transforms
- * - Motor control functions
- * - Statistical functions
- * - Support functions
- * - Interpolation functions
- *
- * The library has separate functions for operating on 8-bit integers, 16-bit integers,
- * 32-bit integer and 32-bit floating-point values.
- *
- * <b>Using the Library</b>
- *
- * The library installer contains prebuilt versions of the libraries in the <code>Lib</code> folder.
- * - arm_cortexM4lf_math.lib (Little endian and Floating Point Unit on Cortex-M4)
- * - arm_cortexM4bf_math.lib (Big endian and Floating Point Unit on Cortex-M4)
- * - arm_cortexM4l_math.lib (Little endian on Cortex-M4)
- * - arm_cortexM4b_math.lib (Big endian on Cortex-M4)
- * - arm_cortexM3l_math.lib (Little endian on Cortex-M3)
- * - arm_cortexM3b_math.lib (Big endian on Cortex-M3)
- * - arm_cortexM0l_math.lib (Little endian on Cortex-M0)
- * - arm_cortexM0b_math.lib (Big endian on Cortex-M3)
- *
- * The library functions are declared in the public file <code>arm_math.h</code> which is placed in the <code>Include</code> folder.
- * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single
- * public header file <code> arm_math.h</code> for Cortex-M4/M3/M0 with little endian and big endian. Same header file will be used for floating point unit(FPU) variants.
- * Define the appropriate pre processor MACRO ARM_MATH_CM4 or ARM_MATH_CM3 or
- * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application.
- *
- * <b>Examples</b>
- *
- * The library ships with a number of examples which demonstrate how to use the library functions.
- *
- * <b>Toolchain Support</b>
- *
- * The library has been developed and tested with MDK-ARM version 4.60.
- * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly.
- *
- * <b>Building the Library</b>
- *
- * The library installer contains project files to re build libraries on MDK Tool chain in the <code>CMSIS\\DSP_Lib\\Source\\ARM</code> folder.
- * - arm_cortexM0b_math.uvproj
- * - arm_cortexM0l_math.uvproj
- * - arm_cortexM3b_math.uvproj
- * - arm_cortexM3l_math.uvproj
- * - arm_cortexM4b_math.uvproj
- * - arm_cortexM4l_math.uvproj
- * - arm_cortexM4bf_math.uvproj
- * - arm_cortexM4lf_math.uvproj
- *
- *
- * The project can be built by opening the appropriate project in MDK-ARM 4.60 chain and defining the optional pre processor MACROs detailed above.
- *
- * <b>Pre-processor Macros</b>
- *
- * Each library project have differant pre-processor macros.
- *
- * - UNALIGNED_SUPPORT_DISABLE:
- *
- * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access
- *
- * - ARM_MATH_BIG_ENDIAN:
- *
- * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets.
- *
- * - ARM_MATH_MATRIX_CHECK:
- *
- * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices
- *
- * - ARM_MATH_ROUNDING:
- *
- * Define macro ARM_MATH_ROUNDING for rounding on support functions
- *
- * - ARM_MATH_CMx:
- *
- * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target
- * and ARM_MATH_CM0 for building library on cortex-M0 target, ARM_MATH_CM0PLUS for building library on cortex-M0+ target.
- *
- * - __FPU_PRESENT:
- *
- * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries
- *
- * <b>Copyright Notice</b>
- *
- * Copyright (C) 2010-2013 ARM Limited. All rights reserved.
- */
-
-
-/**
- * @defgroup groupMath Basic Math Functions
- */
-
-/**
- * @defgroup groupFastMath Fast Math Functions
- * This set of functions provides a fast approximation to sine, cosine, and square root.
- * As compared to most of the other functions in the CMSIS math library, the fast math functions
- * operate on individual values and not arrays.
- * There are separate functions for Q15, Q31, and floating-point data.
- *
- */
-
-/**
- * @defgroup groupCmplxMath Complex Math Functions
- * This set of functions operates on complex data vectors.
- * The data in the complex arrays is stored in an interleaved fashion
- * (real, imag, real, imag, ...).
- * In the API functions, the number of samples in a complex array refers
- * to the number of complex values; the array contains twice this number of
- * real values.
- */
-
-/**
- * @defgroup groupFilters Filtering Functions
- */
-
-/**
- * @defgroup groupMatrix Matrix Functions
- *
- * This set of functions provides basic matrix math operations.
- * The functions operate on matrix data structures. For example,
- * the type
- * definition for the floating-point matrix structure is shown
- * below:
- * <pre>
- * typedef struct
- * {
- * uint16_t numRows; // number of rows of the matrix.
- * uint16_t numCols; // number of columns of the matrix.
- * float32_t *pData; // points to the data of the matrix.
- * } arm_matrix_instance_f32;
- * </pre>
- * There are similar definitions for Q15 and Q31 data types.
- *
- * The structure specifies the size of the matrix and then points to
- * an array of data. The array is of size <code>numRows X numCols</code>
- * and the values are arranged in row order. That is, the
- * matrix element (i, j) is stored at:
- * <pre>
- * pData[i*numCols + j]
- * </pre>
- *
- * \par Init Functions
- * There is an associated initialization function for each type of matrix
- * data structure.
- * The initialization function sets the values of the internal structure fields.
- * Refer to the function <code>arm_mat_init_f32()</code>, <code>arm_mat_init_q31()</code>
- * and <code>arm_mat_init_q15()</code> for floating-point, Q31 and Q15 types, respectively.
- *
- * \par
- * Use of the initialization function is optional. However, if initialization function is used
- * then the instance structure cannot be placed into a const data section.
- * To place the instance structure in a const data
- * section, manually initialize the data structure. For example:
- * <pre>
- * <code>arm_matrix_instance_f32 S = {nRows, nColumns, pData};</code>
- * <code>arm_matrix_instance_q31 S = {nRows, nColumns, pData};</code>
- * <code>arm_matrix_instance_q15 S = {nRows, nColumns, pData};</code>
- * </pre>
- * where <code>nRows</code> specifies the number of rows, <code>nColumns</code>
- * specifies the number of columns, and <code>pData</code> points to the
- * data array.
- *
- * \par Size Checking
- * By default all of the matrix functions perform size checking on the input and
- * output matrices. For example, the matrix addition function verifies that the
- * two input matrices and the output matrix all have the same number of rows and
- * columns. If the size check fails the functions return:
- * <pre>
- * ARM_MATH_SIZE_MISMATCH
- * </pre>
- * Otherwise the functions return
- * <pre>
- * ARM_MATH_SUCCESS
- * </pre>
- * There is some overhead associated with this matrix size checking.
- * The matrix size checking is enabled via the \#define
- * <pre>
- * ARM_MATH_MATRIX_CHECK
- * </pre>
- * within the library project settings. By default this macro is defined
- * and size checking is enabled. By changing the project settings and
- * undefining this macro size checking is eliminated and the functions
- * run a bit faster. With size checking disabled the functions always
- * return <code>ARM_MATH_SUCCESS</code>.
- */
-
-/**
- * @defgroup groupTransforms Transform Functions
- */
-
-/**
- * @defgroup groupController Controller Functions
- */
-
-/**
- * @defgroup groupStats Statistics Functions
- */
-/**
- * @defgroup groupSupport Support Functions
- */
-
-/**
- * @defgroup groupInterpolation Interpolation Functions
- * These functions perform 1- and 2-dimensional interpolation of data.
- * Linear interpolation is used for 1-dimensional data and
- * bilinear interpolation is used for 2-dimensional data.
- */
-
-/**
- * @defgroup groupExamples Examples
- */
-#ifndef _ARM_MATH_H
-#define _ARM_MATH_H
-
-#define __CMSIS_GENERIC /* disable NVIC and Systick functions */
-
-/* PX4 */
-#include <nuttx/config.h>
-#ifdef CONFIG_ARCH_CORTEXM4
-# define ARM_MATH_CM4 1
-#endif
-#ifdef CONFIG_ARCH_CORTEXM3
-# define ARM_MATH_CM3 1
-#endif
-#ifdef CONFIG_ARCH_FPU
-# define __FPU_PRESENT 1
-#endif
-
-#if defined (ARM_MATH_CM4)
-#include "core_cm4.h"
-#elif defined (ARM_MATH_CM3)
-#include "core_cm3.h"
-#elif defined (ARM_MATH_CM0)
-#include "core_cm0.h"
-#define ARM_MATH_CM0_FAMILY
-#elif defined (ARM_MATH_CM0PLUS)
-#include "core_cm0plus.h"
-#define ARM_MATH_CM0_FAMILY
-#else
-#include "ARMCM4.h"
-#warning "Define either ARM_MATH_CM4 OR ARM_MATH_CM3...By Default building on ARM_MATH_CM4....."
-#endif
-
-#undef __CMSIS_GENERIC /* enable NVIC and Systick functions */
-#include "string.h"
-#include "math.h"
-#ifdef __cplusplus
-extern "C"
-{
-#endif
-
-
- /**
- * @brief Macros required for reciprocal calculation in Normalized LMS
- */
-
-#define DELTA_Q31 (0x100)
-#define DELTA_Q15 0x5
-#define INDEX_MASK 0x0000003F
-#ifndef PI
-#define PI 3.14159265358979f
-#endif
-
- /**
- * @brief Macros required for SINE and COSINE Fast math approximations
- */
-
-#define TABLE_SIZE 256
-#define TABLE_SPACING_Q31 0x800000
-#define TABLE_SPACING_Q15 0x80
-
- /**
- * @brief Macros required for SINE and COSINE Controller functions
- */
- /* 1.31(q31) Fixed value of 2/360 */
- /* -1 to +1 is divided into 360 values so total spacing is (2/360) */
-#define INPUT_SPACING 0xB60B61
-
- /**
- * @brief Macro for Unaligned Support
- */
-#ifndef UNALIGNED_SUPPORT_DISABLE
- #define ALIGN4
-#else
- #if defined (__GNUC__)
- #define ALIGN4 __attribute__((aligned(4)))
- #else
- #define ALIGN4 __align(4)
- #endif
-#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */
-
- /**
- * @brief Error status returned by some functions in the library.
- */
-
- typedef enum
- {
- ARM_MATH_SUCCESS = 0, /**< No error */
- ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */
- ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */
- ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation. */
- ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */
- ARM_MATH_SINGULAR = -5, /**< Generated by matrix inversion if the input matrix is singular and cannot be inverted. */
- ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */
- } arm_status;
-
- /**
- * @brief 8-bit fractional data type in 1.7 format.
- */
- typedef int8_t q7_t;
-
- /**
- * @brief 16-bit fractional data type in 1.15 format.
- */
- typedef int16_t q15_t;
-
- /**
- * @brief 32-bit fractional data type in 1.31 format.
- */
- typedef int32_t q31_t;
-
- /**
- * @brief 64-bit fractional data type in 1.63 format.
- */
- typedef int64_t q63_t;
-
- /**
- * @brief 32-bit floating-point type definition.
- */
- typedef float float32_t;
-
- /**
- * @brief 64-bit floating-point type definition.
- */
- typedef double float64_t;
-
- /**
- * @brief definition to read/write two 16 bit values.
- */
-#if defined __CC_ARM
-#define __SIMD32_TYPE int32_t __packed
-#define CMSIS_UNUSED __attribute__((unused))
-#elif defined __ICCARM__
-#define CMSIS_UNUSED
-#define __SIMD32_TYPE int32_t __packed
-#elif defined __GNUC__
-#define __SIMD32_TYPE int32_t
-#define CMSIS_UNUSED __attribute__((unused))
-#else
-#error Unknown compiler
-#endif
-
-#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr))
-#define __SIMD32_CONST(addr) ((__SIMD32_TYPE *)(addr))
-
-#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE *) (addr))
-
-#define __SIMD64(addr) (*(int64_t **) & (addr))
-
-#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY)
- /**
- * @brief definition to pack two 16 bit values.
- */
-#define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \
- (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) )
-#define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \
- (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) )
-
-#endif
-
-
- /**
- * @brief definition to pack four 8 bit values.
- */
-#ifndef ARM_MATH_BIG_ENDIAN
-
-#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \
- (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \
- (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \
- (((int32_t)(v3) << 24) & (int32_t)0xFF000000) )
-#else
-
-#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \
- (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \
- (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \
- (((int32_t)(v0) << 24) & (int32_t)0xFF000000) )
-
-#endif
-
-
- /**
- * @brief Clips Q63 to Q31 values.
- */
- static __INLINE q31_t clip_q63_to_q31(
- q63_t x)
- {
- return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ?
- ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x;
- }
-
- /**
- * @brief Clips Q63 to Q15 values.
- */
- static __INLINE q15_t clip_q63_to_q15(
- q63_t x)
- {
- return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ?
- ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15);
- }
-
- /**
- * @brief Clips Q31 to Q7 values.
- */
- static __INLINE q7_t clip_q31_to_q7(
- q31_t x)
- {
- return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ?
- ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x;
- }
-
- /**
- * @brief Clips Q31 to Q15 values.
- */
- static __INLINE q15_t clip_q31_to_q15(
- q31_t x)
- {
- return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ?
- ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x;
- }
-
- /**
- * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format.
- */
-
- static __INLINE q63_t mult32x64(
- q63_t x,
- q31_t y)
- {
- return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) +
- (((q63_t) (x >> 32) * y)));
- }
-
-
-#if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM )
-#define __CLZ __clz
-#endif
-
-#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ||(defined (__GNUC__)) || defined (__TASKING__) )
-
- static __INLINE uint32_t __CLZ(
- q31_t data);
-
-
- static __INLINE uint32_t __CLZ(
- q31_t data)
- {
- uint32_t count = 0;
- uint32_t mask = 0x80000000;
-
- while((data & mask) == 0)
- {
- count += 1u;
- mask = mask >> 1u;
- }
-
- return (count);
-
- }
-
-#endif
-
- /**
- * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type.
- */
-
- static __INLINE uint32_t arm_recip_q31(
- q31_t in,
- q31_t * dst,
- q31_t * pRecipTable)
- {
-
- uint32_t out, tempVal;
- uint32_t index, i;
- uint32_t signBits;
-
- if(in > 0)
- {
- signBits = __CLZ(in) - 1;
- }
- else
- {
- signBits = __CLZ(-in) - 1;
- }
-
- /* Convert input sample to 1.31 format */
- in = in << signBits;
-
- /* calculation of index for initial approximated Val */
- index = (uint32_t) (in >> 24u);
- index = (index & INDEX_MASK);
-
- /* 1.31 with exp 1 */
- out = pRecipTable[index];
-
- /* calculation of reciprocal value */
- /* running approximation for two iterations */
- for (i = 0u; i < 2u; i++)
- {
- tempVal = (q31_t) (((q63_t) in * out) >> 31u);
- tempVal = 0x7FFFFFFF - tempVal;
- /* 1.31 with exp 1 */
- //out = (q31_t) (((q63_t) out * tempVal) >> 30u);
- out = (q31_t) clip_q63_to_q31(((q63_t) out * tempVal) >> 30u);
- }
-
- /* write output */
- *dst = out;
-
- /* return num of signbits of out = 1/in value */
- return (signBits + 1u);
-
- }
-
- /**
- * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type.
- */
- static __INLINE uint32_t arm_recip_q15(
- q15_t in,
- q15_t * dst,
- q15_t * pRecipTable)
- {
-
- uint32_t out = 0, tempVal = 0;
- uint32_t index = 0, i = 0;
- uint32_t signBits = 0;
-
- if(in > 0)
- {
- signBits = __CLZ(in) - 17;
- }
- else
- {
- signBits = __CLZ(-in) - 17;
- }
-
- /* Convert input sample to 1.15 format */
- in = in << signBits;
-
- /* calculation of index for initial approximated Val */
- index = in >> 8;
- index = (index & INDEX_MASK);
-
- /* 1.15 with exp 1 */
- out = pRecipTable[index];
-
- /* calculation of reciprocal value */
- /* running approximation for two iterations */
- for (i = 0; i < 2; i++)
- {
- tempVal = (q15_t) (((q31_t) in * out) >> 15);
- tempVal = 0x7FFF - tempVal;
- /* 1.15 with exp 1 */
- out = (q15_t) (((q31_t) out * tempVal) >> 14);
- }
-
- /* write output */
- *dst = out;
-
- /* return num of signbits of out = 1/in value */
- return (signBits + 1);
-
- }
-
-
- /*
- * @brief C custom defined intrinisic function for only M0 processors
- */
-#if defined(ARM_MATH_CM0_FAMILY)
-
- static __INLINE q31_t __SSAT(
- q31_t x,
- uint32_t y)
- {
- int32_t posMax, negMin;
- uint32_t i;
-
- posMax = 1;
- for (i = 0; i < (y - 1); i++)
- {
- posMax = posMax * 2;
- }
-
- if(x > 0)
- {
- posMax = (posMax - 1);
-
- if(x > posMax)
- {
- x = posMax;
- }
- }
- else
- {
- negMin = -posMax;
-
- if(x < negMin)
- {
- x = negMin;
- }
- }
- return (x);
-
-
- }
-
-#endif /* end of ARM_MATH_CM0_FAMILY */
-
-
-
- /*
- * @brief C custom defined intrinsic function for M3 and M0 processors
- */
-#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY)
-
- /*
- * @brief C custom defined QADD8 for M3 and M0 processors
- */
- static __INLINE q31_t __QADD8(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q7_t r, s, t, u;
-
- r = (q7_t) x;
- s = (q7_t) y;
-
- r = __SSAT((q31_t) (r + s), 8);
- s = __SSAT(((q31_t) (((x << 16) >> 24) + ((y << 16) >> 24))), 8);
- t = __SSAT(((q31_t) (((x << 8) >> 24) + ((y << 8) >> 24))), 8);
- u = __SSAT(((q31_t) ((x >> 24) + (y >> 24))), 8);
-
- sum =
- (((q31_t) u << 24) & 0xFF000000) | (((q31_t) t << 16) & 0x00FF0000) |
- (((q31_t) s << 8) & 0x0000FF00) | (r & 0x000000FF);
-
- return sum;
-
- }
-
- /*
- * @brief C custom defined QSUB8 for M3 and M0 processors
- */
- static __INLINE q31_t __QSUB8(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q31_t r, s, t, u;
-
- r = (q7_t) x;
- s = (q7_t) y;
-
- r = __SSAT((r - s), 8);
- s = __SSAT(((q31_t) (((x << 16) >> 24) - ((y << 16) >> 24))), 8) << 8;
- t = __SSAT(((q31_t) (((x << 8) >> 24) - ((y << 8) >> 24))), 8) << 16;
- u = __SSAT(((q31_t) ((x >> 24) - (y >> 24))), 8) << 24;
-
- sum =
- (u & 0xFF000000) | (t & 0x00FF0000) | (s & 0x0000FF00) | (r &
- 0x000000FF);
-
- return sum;
- }
-
- /*
- * @brief C custom defined QADD16 for M3 and M0 processors
- */
-
- /*
- * @brief C custom defined QADD16 for M3 and M0 processors
- */
- static __INLINE q31_t __QADD16(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q31_t r, s;
-
- r = (short) x;
- s = (short) y;
-
- r = __SSAT(r + s, 16);
- s = __SSAT(((q31_t) ((x >> 16) + (y >> 16))), 16) << 16;
-
- sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
-
- return sum;
-
- }
-
- /*
- * @brief C custom defined SHADD16 for M3 and M0 processors
- */
- static __INLINE q31_t __SHADD16(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q31_t r, s;
-
- r = (short) x;
- s = (short) y;
-
- r = ((r >> 1) + (s >> 1));
- s = ((q31_t) ((x >> 17) + (y >> 17))) << 16;
-
- sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
-
- return sum;
-
- }
-
- /*
- * @brief C custom defined QSUB16 for M3 and M0 processors
- */
- static __INLINE q31_t __QSUB16(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q31_t r, s;
-
- r = (short) x;
- s = (short) y;
-
- r = __SSAT(r - s, 16);
- s = __SSAT(((q31_t) ((x >> 16) - (y >> 16))), 16) << 16;
-
- sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
-
- return sum;
- }
-
- /*
- * @brief C custom defined SHSUB16 for M3 and M0 processors
- */
- static __INLINE q31_t __SHSUB16(
- q31_t x,
- q31_t y)
- {
-
- q31_t diff;
- q31_t r, s;
-
- r = (short) x;
- s = (short) y;
-
- r = ((r >> 1) - (s >> 1));
- s = (((x >> 17) - (y >> 17)) << 16);
-
- diff = (s & 0xFFFF0000) | (r & 0x0000FFFF);
-
- return diff;
- }
-
- /*
- * @brief C custom defined QASX for M3 and M0 processors
- */
- static __INLINE q31_t __QASX(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum = 0;
-
- sum =
- ((sum +
- clip_q31_to_q15((q31_t) ((short) (x >> 16) + (short) y))) << 16) +
- clip_q31_to_q15((q31_t) ((short) x - (short) (y >> 16)));
-
- return sum;
- }
-
- /*
- * @brief C custom defined SHASX for M3 and M0 processors
- */
- static __INLINE q31_t __SHASX(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q31_t r, s;
-
- r = (short) x;
- s = (short) y;
-
- r = ((r >> 1) - (y >> 17));
- s = (((x >> 17) + (s >> 1)) << 16);
-
- sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
-
- return sum;
- }
-
-
- /*
- * @brief C custom defined QSAX for M3 and M0 processors
- */
- static __INLINE q31_t __QSAX(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum = 0;
-
- sum =
- ((sum +
- clip_q31_to_q15((q31_t) ((short) (x >> 16) - (short) y))) << 16) +
- clip_q31_to_q15((q31_t) ((short) x + (short) (y >> 16)));
-
- return sum;
- }
-
- /*
- * @brief C custom defined SHSAX for M3 and M0 processors
- */
- static __INLINE q31_t __SHSAX(
- q31_t x,
- q31_t y)
- {
-
- q31_t sum;
- q31_t r, s;
-
- r = (short) x;
- s = (short) y;
-
- r = ((r >> 1) + (y >> 17));
- s = (((x >> 17) - (s >> 1)) << 16);
-
- sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
-
- return sum;
- }
-
- /*
- * @brief C custom defined SMUSDX for M3 and M0 processors
- */
- static __INLINE q31_t __SMUSDX(
- q31_t x,
- q31_t y)
- {
-
- return ((q31_t) (((short) x * (short) (y >> 16)) -
- ((short) (x >> 16) * (short) y)));
- }
-
- /*
- * @brief C custom defined SMUADX for M3 and M0 processors
- */
- static __INLINE q31_t __SMUADX(
- q31_t x,
- q31_t y)
- {
-
- return ((q31_t) (((short) x * (short) (y >> 16)) +
- ((short) (x >> 16) * (short) y)));
- }
-
- /*
- * @brief C custom defined QADD for M3 and M0 processors
- */
- static __INLINE q31_t __QADD(
- q31_t x,
- q31_t y)
- {
- return clip_q63_to_q31((q63_t) x + y);
- }
-
- /*
- * @brief C custom defined QSUB for M3 and M0 processors
- */
- static __INLINE q31_t __QSUB(
- q31_t x,
- q31_t y)
- {
- return clip_q63_to_q31((q63_t) x - y);
- }
-
- /*
- * @brief C custom defined SMLAD for M3 and M0 processors
- */
- static __INLINE q31_t __SMLAD(
- q31_t x,
- q31_t y,
- q31_t sum)
- {
-
- return (sum + ((short) (x >> 16) * (short) (y >> 16)) +
- ((short) x * (short) y));
- }
-
- /*
- * @brief C custom defined SMLADX for M3 and M0 processors
- */
- static __INLINE q31_t __SMLADX(
- q31_t x,
- q31_t y,
- q31_t sum)
- {
-
- return (sum + ((short) (x >> 16) * (short) (y)) +
- ((short) x * (short) (y >> 16)));
- }
-
- /*
- * @brief C custom defined SMLSDX for M3 and M0 processors
- */
- static __INLINE q31_t __SMLSDX(
- q31_t x,
- q31_t y,
- q31_t sum)
- {
-
- return (sum - ((short) (x >> 16) * (short) (y)) +
- ((short) x * (short) (y >> 16)));
- }
-
- /*
- * @brief C custom defined SMLALD for M3 and M0 processors
- */
- static __INLINE q63_t __SMLALD(
- q31_t x,
- q31_t y,
- q63_t sum)
- {
-
- return (sum + ((short) (x >> 16) * (short) (y >> 16)) +
- ((short) x * (short) y));
- }
-
- /*
- * @brief C custom defined SMLALDX for M3 and M0 processors
- */
- static __INLINE q63_t __SMLALDX(
- q31_t x,
- q31_t y,
- q63_t sum)
- {
-
- return (sum + ((short) (x >> 16) * (short) y)) +
- ((short) x * (short) (y >> 16));
- }
-
- /*
- * @brief C custom defined SMUAD for M3 and M0 processors
- */
- static __INLINE q31_t __SMUAD(
- q31_t x,
- q31_t y)
- {
-
- return (((x >> 16) * (y >> 16)) +
- (((x << 16) >> 16) * ((y << 16) >> 16)));
- }
-
- /*
- * @brief C custom defined SMUSD for M3 and M0 processors
- */
- static __INLINE q31_t __SMUSD(
- q31_t x,
- q31_t y)
- {
-
- return (-((x >> 16) * (y >> 16)) +
- (((x << 16) >> 16) * ((y << 16) >> 16)));
- }
-
-
- /*
- * @brief C custom defined SXTB16 for M3 and M0 processors
- */
- static __INLINE q31_t __SXTB16(
- q31_t x)
- {
-
- return ((((x << 24) >> 24) & 0x0000FFFF) |
- (((x << 8) >> 8) & 0xFFFF0000));
- }
-
-
-#endif /* defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) */
-
-
- /**
- * @brief Instance structure for the Q7 FIR filter.
- */
- typedef struct
- {
- uint16_t numTaps; /**< number of filter coefficients in the filter. */
- q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- } arm_fir_instance_q7;
-
- /**
- * @brief Instance structure for the Q15 FIR filter.
- */
- typedef struct
- {
- uint16_t numTaps; /**< number of filter coefficients in the filter. */
- q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- } arm_fir_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 FIR filter.
- */
- typedef struct
- {
- uint16_t numTaps; /**< number of filter coefficients in the filter. */
- q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- } arm_fir_instance_q31;
-
- /**
- * @brief Instance structure for the floating-point FIR filter.
- */
- typedef struct
- {
- uint16_t numTaps; /**< number of filter coefficients in the filter. */
- float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- } arm_fir_instance_f32;
-
-
- /**
- * @brief Processing function for the Q7 FIR filter.
- * @param[in] *S points to an instance of the Q7 FIR filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_q7(
- const arm_fir_instance_q7 * S,
- q7_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the Q7 FIR filter.
- * @param[in,out] *S points to an instance of the Q7 FIR structure.
- * @param[in] numTaps Number of filter coefficients in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of samples that are processed.
- * @return none
- */
- void arm_fir_init_q7(
- arm_fir_instance_q7 * S,
- uint16_t numTaps,
- q7_t * pCoeffs,
- q7_t * pState,
- uint32_t blockSize);
-
-
- /**
- * @brief Processing function for the Q15 FIR filter.
- * @param[in] *S points to an instance of the Q15 FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_q15(
- const arm_fir_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the fast Q15 FIR filter for Cortex-M3 and Cortex-M4.
- * @param[in] *S points to an instance of the Q15 FIR filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_fast_q15(
- const arm_fir_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q15 FIR filter.
- * @param[in,out] *S points to an instance of the Q15 FIR filter structure.
- * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of samples that are processed at a time.
- * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_ARGUMENT_ERROR if
- * <code>numTaps</code> is not a supported value.
- */
-
- arm_status arm_fir_init_q15(
- arm_fir_instance_q15 * S,
- uint16_t numTaps,
- q15_t * pCoeffs,
- q15_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q31 FIR filter.
- * @param[in] *S points to an instance of the Q31 FIR filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_q31(
- const arm_fir_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the fast Q31 FIR filter for Cortex-M3 and Cortex-M4.
- * @param[in] *S points to an instance of the Q31 FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_fast_q31(
- const arm_fir_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q31 FIR filter.
- * @param[in,out] *S points to an instance of the Q31 FIR structure.
- * @param[in] numTaps Number of filter coefficients in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of samples that are processed at a time.
- * @return none.
- */
- void arm_fir_init_q31(
- arm_fir_instance_q31 * S,
- uint16_t numTaps,
- q31_t * pCoeffs,
- q31_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the floating-point FIR filter.
- * @param[in] *S points to an instance of the floating-point FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_f32(
- const arm_fir_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the floating-point FIR filter.
- * @param[in,out] *S points to an instance of the floating-point FIR filter structure.
- * @param[in] numTaps Number of filter coefficients in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of samples that are processed at a time.
- * @return none.
- */
- void arm_fir_init_f32(
- arm_fir_instance_f32 * S,
- uint16_t numTaps,
- float32_t * pCoeffs,
- float32_t * pState,
- uint32_t blockSize);
-
-
- /**
- * @brief Instance structure for the Q15 Biquad cascade filter.
- */
- typedef struct
- {
- int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
- q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
- q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
- int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */
-
- } arm_biquad_casd_df1_inst_q15;
-
-
- /**
- * @brief Instance structure for the Q31 Biquad cascade filter.
- */
- typedef struct
- {
- uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
- q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
- q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
- uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */
-
- } arm_biquad_casd_df1_inst_q31;
-
- /**
- * @brief Instance structure for the floating-point Biquad cascade filter.
- */
- typedef struct
- {
- uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
- float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
- float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
-
-
- } arm_biquad_casd_df1_inst_f32;
-
-
-
- /**
- * @brief Processing function for the Q15 Biquad cascade filter.
- * @param[in] *S points to an instance of the Q15 Biquad cascade structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cascade_df1_q15(
- const arm_biquad_casd_df1_inst_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q15 Biquad cascade filter.
- * @param[in,out] *S points to an instance of the Q15 Biquad cascade structure.
- * @param[in] numStages number of 2nd order stages in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format
- * @return none
- */
-
- void arm_biquad_cascade_df1_init_q15(
- arm_biquad_casd_df1_inst_q15 * S,
- uint8_t numStages,
- q15_t * pCoeffs,
- q15_t * pState,
- int8_t postShift);
-
-
- /**
- * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4.
- * @param[in] *S points to an instance of the Q15 Biquad cascade structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cascade_df1_fast_q15(
- const arm_biquad_casd_df1_inst_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Processing function for the Q31 Biquad cascade filter
- * @param[in] *S points to an instance of the Q31 Biquad cascade structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cascade_df1_q31(
- const arm_biquad_casd_df1_inst_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4.
- * @param[in] *S points to an instance of the Q31 Biquad cascade structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cascade_df1_fast_q31(
- const arm_biquad_casd_df1_inst_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q31 Biquad cascade filter.
- * @param[in,out] *S points to an instance of the Q31 Biquad cascade structure.
- * @param[in] numStages number of 2nd order stages in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format
- * @return none
- */
-
- void arm_biquad_cascade_df1_init_q31(
- arm_biquad_casd_df1_inst_q31 * S,
- uint8_t numStages,
- q31_t * pCoeffs,
- q31_t * pState,
- int8_t postShift);
-
- /**
- * @brief Processing function for the floating-point Biquad cascade filter.
- * @param[in] *S points to an instance of the floating-point Biquad cascade structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cascade_df1_f32(
- const arm_biquad_casd_df1_inst_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the floating-point Biquad cascade filter.
- * @param[in,out] *S points to an instance of the floating-point Biquad cascade structure.
- * @param[in] numStages number of 2nd order stages in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @return none
- */
-
- void arm_biquad_cascade_df1_init_f32(
- arm_biquad_casd_df1_inst_f32 * S,
- uint8_t numStages,
- float32_t * pCoeffs,
- float32_t * pState);
-
-
- /**
- * @brief Instance structure for the floating-point matrix structure.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows of the matrix. */
- uint16_t numCols; /**< number of columns of the matrix. */
- float32_t *pData; /**< points to the data of the matrix. */
- } arm_matrix_instance_f32;
-
- /**
- * @brief Instance structure for the Q15 matrix structure.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows of the matrix. */
- uint16_t numCols; /**< number of columns of the matrix. */
- q15_t *pData; /**< points to the data of the matrix. */
-
- } arm_matrix_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 matrix structure.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows of the matrix. */
- uint16_t numCols; /**< number of columns of the matrix. */
- q31_t *pData; /**< points to the data of the matrix. */
-
- } arm_matrix_instance_q31;
-
-
-
- /**
- * @brief Floating-point matrix addition.
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_add_f32(
- const arm_matrix_instance_f32 * pSrcA,
- const arm_matrix_instance_f32 * pSrcB,
- arm_matrix_instance_f32 * pDst);
-
- /**
- * @brief Q15 matrix addition.
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_add_q15(
- const arm_matrix_instance_q15 * pSrcA,
- const arm_matrix_instance_q15 * pSrcB,
- arm_matrix_instance_q15 * pDst);
-
- /**
- * @brief Q31 matrix addition.
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_add_q31(
- const arm_matrix_instance_q31 * pSrcA,
- const arm_matrix_instance_q31 * pSrcB,
- arm_matrix_instance_q31 * pDst);
-
-
- /**
- * @brief Floating-point matrix transpose.
- * @param[in] *pSrc points to the input matrix
- * @param[out] *pDst points to the output matrix
- * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
- * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_trans_f32(
- const arm_matrix_instance_f32 * pSrc,
- arm_matrix_instance_f32 * pDst);
-
-
- /**
- * @brief Q15 matrix transpose.
- * @param[in] *pSrc points to the input matrix
- * @param[out] *pDst points to the output matrix
- * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
- * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_trans_q15(
- const arm_matrix_instance_q15 * pSrc,
- arm_matrix_instance_q15 * pDst);
-
- /**
- * @brief Q31 matrix transpose.
- * @param[in] *pSrc points to the input matrix
- * @param[out] *pDst points to the output matrix
- * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
- * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_trans_q31(
- const arm_matrix_instance_q31 * pSrc,
- arm_matrix_instance_q31 * pDst);
-
-
- /**
- * @brief Floating-point matrix multiplication
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_mult_f32(
- const arm_matrix_instance_f32 * pSrcA,
- const arm_matrix_instance_f32 * pSrcB,
- arm_matrix_instance_f32 * pDst);
-
- /**
- * @brief Q15 matrix multiplication
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @param[in] *pState points to the array for storing intermediate results
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_mult_q15(
- const arm_matrix_instance_q15 * pSrcA,
- const arm_matrix_instance_q15 * pSrcB,
- arm_matrix_instance_q15 * pDst,
- q15_t * pState);
-
- /**
- * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @param[in] *pState points to the array for storing intermediate results
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_mult_fast_q15(
- const arm_matrix_instance_q15 * pSrcA,
- const arm_matrix_instance_q15 * pSrcB,
- arm_matrix_instance_q15 * pDst,
- q15_t * pState);
-
- /**
- * @brief Q31 matrix multiplication
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_mult_q31(
- const arm_matrix_instance_q31 * pSrcA,
- const arm_matrix_instance_q31 * pSrcB,
- arm_matrix_instance_q31 * pDst);
-
- /**
- * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_mult_fast_q31(
- const arm_matrix_instance_q31 * pSrcA,
- const arm_matrix_instance_q31 * pSrcB,
- arm_matrix_instance_q31 * pDst);
-
-
- /**
- * @brief Floating-point matrix subtraction
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_sub_f32(
- const arm_matrix_instance_f32 * pSrcA,
- const arm_matrix_instance_f32 * pSrcB,
- arm_matrix_instance_f32 * pDst);
-
- /**
- * @brief Q15 matrix subtraction
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_sub_q15(
- const arm_matrix_instance_q15 * pSrcA,
- const arm_matrix_instance_q15 * pSrcB,
- arm_matrix_instance_q15 * pDst);
-
- /**
- * @brief Q31 matrix subtraction
- * @param[in] *pSrcA points to the first input matrix structure
- * @param[in] *pSrcB points to the second input matrix structure
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_sub_q31(
- const arm_matrix_instance_q31 * pSrcA,
- const arm_matrix_instance_q31 * pSrcB,
- arm_matrix_instance_q31 * pDst);
-
- /**
- * @brief Floating-point matrix scaling.
- * @param[in] *pSrc points to the input matrix
- * @param[in] scale scale factor
- * @param[out] *pDst points to the output matrix
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_scale_f32(
- const arm_matrix_instance_f32 * pSrc,
- float32_t scale,
- arm_matrix_instance_f32 * pDst);
-
- /**
- * @brief Q15 matrix scaling.
- * @param[in] *pSrc points to input matrix
- * @param[in] scaleFract fractional portion of the scale factor
- * @param[in] shift number of bits to shift the result by
- * @param[out] *pDst points to output matrix
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_scale_q15(
- const arm_matrix_instance_q15 * pSrc,
- q15_t scaleFract,
- int32_t shift,
- arm_matrix_instance_q15 * pDst);
-
- /**
- * @brief Q31 matrix scaling.
- * @param[in] *pSrc points to input matrix
- * @param[in] scaleFract fractional portion of the scale factor
- * @param[in] shift number of bits to shift the result by
- * @param[out] *pDst points to output matrix structure
- * @return The function returns either
- * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
- */
-
- arm_status arm_mat_scale_q31(
- const arm_matrix_instance_q31 * pSrc,
- q31_t scaleFract,
- int32_t shift,
- arm_matrix_instance_q31 * pDst);
-
-
- /**
- * @brief Q31 matrix initialization.
- * @param[in,out] *S points to an instance of the floating-point matrix structure.
- * @param[in] nRows number of rows in the matrix.
- * @param[in] nColumns number of columns in the matrix.
- * @param[in] *pData points to the matrix data array.
- * @return none
- */
-
- void arm_mat_init_q31(
- arm_matrix_instance_q31 * S,
- uint16_t nRows,
- uint16_t nColumns,
- q31_t * pData);
-
- /**
- * @brief Q15 matrix initialization.
- * @param[in,out] *S points to an instance of the floating-point matrix structure.
- * @param[in] nRows number of rows in the matrix.
- * @param[in] nColumns number of columns in the matrix.
- * @param[in] *pData points to the matrix data array.
- * @return none
- */
-
- void arm_mat_init_q15(
- arm_matrix_instance_q15 * S,
- uint16_t nRows,
- uint16_t nColumns,
- q15_t * pData);
-
- /**
- * @brief Floating-point matrix initialization.
- * @param[in,out] *S points to an instance of the floating-point matrix structure.
- * @param[in] nRows number of rows in the matrix.
- * @param[in] nColumns number of columns in the matrix.
- * @param[in] *pData points to the matrix data array.
- * @return none
- */
-
- void arm_mat_init_f32(
- arm_matrix_instance_f32 * S,
- uint16_t nRows,
- uint16_t nColumns,
- float32_t * pData);
-
-
-
- /**
- * @brief Instance structure for the Q15 PID Control.
- */
- typedef struct
- {
- q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
-#ifdef ARM_MATH_CM0_FAMILY
- q15_t A1;
- q15_t A2;
-#else
- q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/
-#endif
- q15_t state[3]; /**< The state array of length 3. */
- q15_t Kp; /**< The proportional gain. */
- q15_t Ki; /**< The integral gain. */
- q15_t Kd; /**< The derivative gain. */
- } arm_pid_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 PID Control.
- */
- typedef struct
- {
- q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
- q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */
- q31_t A2; /**< The derived gain, A2 = Kd . */
- q31_t state[3]; /**< The state array of length 3. */
- q31_t Kp; /**< The proportional gain. */
- q31_t Ki; /**< The integral gain. */
- q31_t Kd; /**< The derivative gain. */
-
- } arm_pid_instance_q31;
-
- /**
- * @brief Instance structure for the floating-point PID Control.
- */
- typedef struct
- {
- float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
- float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */
- float32_t A2; /**< The derived gain, A2 = Kd . */
- float32_t state[3]; /**< The state array of length 3. */
- float32_t Kp; /**< The proportional gain. */
- float32_t Ki; /**< The integral gain. */
- float32_t Kd; /**< The derivative gain. */
- } arm_pid_instance_f32;
-
-
-
- /**
- * @brief Initialization function for the floating-point PID Control.
- * @param[in,out] *S points to an instance of the PID structure.
- * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
- * @return none.
- */
- void arm_pid_init_f32(
- arm_pid_instance_f32 * S,
- int32_t resetStateFlag);
-
- /**
- * @brief Reset function for the floating-point PID Control.
- * @param[in,out] *S is an instance of the floating-point PID Control structure
- * @return none
- */
- void arm_pid_reset_f32(
- arm_pid_instance_f32 * S);
-
-
- /**
- * @brief Initialization function for the Q31 PID Control.
- * @param[in,out] *S points to an instance of the Q15 PID structure.
- * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
- * @return none.
- */
- void arm_pid_init_q31(
- arm_pid_instance_q31 * S,
- int32_t resetStateFlag);
-
-
- /**
- * @brief Reset function for the Q31 PID Control.
- * @param[in,out] *S points to an instance of the Q31 PID Control structure
- * @return none
- */
-
- void arm_pid_reset_q31(
- arm_pid_instance_q31 * S);
-
- /**
- * @brief Initialization function for the Q15 PID Control.
- * @param[in,out] *S points to an instance of the Q15 PID structure.
- * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
- * @return none.
- */
- void arm_pid_init_q15(
- arm_pid_instance_q15 * S,
- int32_t resetStateFlag);
-
- /**
- * @brief Reset function for the Q15 PID Control.
- * @param[in,out] *S points to an instance of the q15 PID Control structure
- * @return none
- */
- void arm_pid_reset_q15(
- arm_pid_instance_q15 * S);
-
-
- /**
- * @brief Instance structure for the floating-point Linear Interpolate function.
- */
- typedef struct
- {
- uint32_t nValues; /**< nValues */
- float32_t x1; /**< x1 */
- float32_t xSpacing; /**< xSpacing */
- float32_t *pYData; /**< pointer to the table of Y values */
- } arm_linear_interp_instance_f32;
-
- /**
- * @brief Instance structure for the floating-point bilinear interpolation function.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows in the data table. */
- uint16_t numCols; /**< number of columns in the data table. */
- float32_t *pData; /**< points to the data table. */
- } arm_bilinear_interp_instance_f32;
-
- /**
- * @brief Instance structure for the Q31 bilinear interpolation function.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows in the data table. */
- uint16_t numCols; /**< number of columns in the data table. */
- q31_t *pData; /**< points to the data table. */
- } arm_bilinear_interp_instance_q31;
-
- /**
- * @brief Instance structure for the Q15 bilinear interpolation function.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows in the data table. */
- uint16_t numCols; /**< number of columns in the data table. */
- q15_t *pData; /**< points to the data table. */
- } arm_bilinear_interp_instance_q15;
-
- /**
- * @brief Instance structure for the Q15 bilinear interpolation function.
- */
-
- typedef struct
- {
- uint16_t numRows; /**< number of rows in the data table. */
- uint16_t numCols; /**< number of columns in the data table. */
- q7_t *pData; /**< points to the data table. */
- } arm_bilinear_interp_instance_q7;
-
-
- /**
- * @brief Q7 vector multiplication.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_mult_q7(
- q7_t * pSrcA,
- q7_t * pSrcB,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q15 vector multiplication.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_mult_q15(
- q15_t * pSrcA,
- q15_t * pSrcB,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q31 vector multiplication.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_mult_q31(
- q31_t * pSrcA,
- q31_t * pSrcB,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Floating-point vector multiplication.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_mult_f32(
- float32_t * pSrcA,
- float32_t * pSrcB,
- float32_t * pDst,
- uint32_t blockSize);
-
-
-
-
-
-
- /**
- * @brief Instance structure for the Q15 CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
- uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
- q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */
- uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
- } arm_cfft_radix2_instance_q15;
-
- arm_status arm_cfft_radix2_init_q15(
- arm_cfft_radix2_instance_q15 * S,
- uint16_t fftLen,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
- void arm_cfft_radix2_q15(
- const arm_cfft_radix2_instance_q15 * S,
- q15_t * pSrc);
-
-
-
- /**
- * @brief Instance structure for the Q15 CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
- uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
- q15_t *pTwiddle; /**< points to the twiddle factor table. */
- uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
- } arm_cfft_radix4_instance_q15;
-
- arm_status arm_cfft_radix4_init_q15(
- arm_cfft_radix4_instance_q15 * S,
- uint16_t fftLen,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
- void arm_cfft_radix4_q15(
- const arm_cfft_radix4_instance_q15 * S,
- q15_t * pSrc);
-
- /**
- * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
- uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
- q31_t *pTwiddle; /**< points to the Twiddle factor table. */
- uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
- } arm_cfft_radix2_instance_q31;
-
- arm_status arm_cfft_radix2_init_q31(
- arm_cfft_radix2_instance_q31 * S,
- uint16_t fftLen,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
- void arm_cfft_radix2_q31(
- const arm_cfft_radix2_instance_q31 * S,
- q31_t * pSrc);
-
- /**
- * @brief Instance structure for the Q31 CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
- uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
- q31_t *pTwiddle; /**< points to the twiddle factor table. */
- uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
- } arm_cfft_radix4_instance_q31;
-
-
- void arm_cfft_radix4_q31(
- const arm_cfft_radix4_instance_q31 * S,
- q31_t * pSrc);
-
- arm_status arm_cfft_radix4_init_q31(
- arm_cfft_radix4_instance_q31 * S,
- uint16_t fftLen,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
- /**
- * @brief Instance structure for the floating-point CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
- uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
- float32_t *pTwiddle; /**< points to the Twiddle factor table. */
- uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
- float32_t onebyfftLen; /**< value of 1/fftLen. */
- } arm_cfft_radix2_instance_f32;
-
-/* Deprecated */
- arm_status arm_cfft_radix2_init_f32(
- arm_cfft_radix2_instance_f32 * S,
- uint16_t fftLen,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
-/* Deprecated */
- void arm_cfft_radix2_f32(
- const arm_cfft_radix2_instance_f32 * S,
- float32_t * pSrc);
-
- /**
- * @brief Instance structure for the floating-point CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
- uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
- float32_t *pTwiddle; /**< points to the Twiddle factor table. */
- uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
- float32_t onebyfftLen; /**< value of 1/fftLen. */
- } arm_cfft_radix4_instance_f32;
-
-/* Deprecated */
- arm_status arm_cfft_radix4_init_f32(
- arm_cfft_radix4_instance_f32 * S,
- uint16_t fftLen,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
-/* Deprecated */
- void arm_cfft_radix4_f32(
- const arm_cfft_radix4_instance_f32 * S,
- float32_t * pSrc);
-
- /**
- * @brief Instance structure for the floating-point CFFT/CIFFT function.
- */
-
- typedef struct
- {
- uint16_t fftLen; /**< length of the FFT. */
- const float32_t *pTwiddle; /**< points to the Twiddle factor table. */
- const uint16_t *pBitRevTable; /**< points to the bit reversal table. */
- uint16_t bitRevLength; /**< bit reversal table length. */
- } arm_cfft_instance_f32;
-
- void arm_cfft_f32(
- const arm_cfft_instance_f32 * S,
- float32_t * p1,
- uint8_t ifftFlag,
- uint8_t bitReverseFlag);
-
- /**
- * @brief Instance structure for the Q15 RFFT/RIFFT function.
- */
-
- typedef struct
- {
- uint32_t fftLenReal; /**< length of the real FFT. */
- uint32_t fftLenBy2; /**< length of the complex FFT. */
- uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
- uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
- uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
- q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
- arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */
- } arm_rfft_instance_q15;
-
- arm_status arm_rfft_init_q15(
- arm_rfft_instance_q15 * S,
- arm_cfft_radix4_instance_q15 * S_CFFT,
- uint32_t fftLenReal,
- uint32_t ifftFlagR,
- uint32_t bitReverseFlag);
-
- void arm_rfft_q15(
- const arm_rfft_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst);
-
- /**
- * @brief Instance structure for the Q31 RFFT/RIFFT function.
- */
-
- typedef struct
- {
- uint32_t fftLenReal; /**< length of the real FFT. */
- uint32_t fftLenBy2; /**< length of the complex FFT. */
- uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
- uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
- uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
- q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
- arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */
- } arm_rfft_instance_q31;
-
- arm_status arm_rfft_init_q31(
- arm_rfft_instance_q31 * S,
- arm_cfft_radix4_instance_q31 * S_CFFT,
- uint32_t fftLenReal,
- uint32_t ifftFlagR,
- uint32_t bitReverseFlag);
-
- void arm_rfft_q31(
- const arm_rfft_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst);
-
- /**
- * @brief Instance structure for the floating-point RFFT/RIFFT function.
- */
-
- typedef struct
- {
- uint32_t fftLenReal; /**< length of the real FFT. */
- uint16_t fftLenBy2; /**< length of the complex FFT. */
- uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
- uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
- uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
- float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
- float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
- arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */
- } arm_rfft_instance_f32;
-
- arm_status arm_rfft_init_f32(
- arm_rfft_instance_f32 * S,
- arm_cfft_radix4_instance_f32 * S_CFFT,
- uint32_t fftLenReal,
- uint32_t ifftFlagR,
- uint32_t bitReverseFlag);
-
- void arm_rfft_f32(
- const arm_rfft_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst);
-
- /**
- * @brief Instance structure for the floating-point RFFT/RIFFT function.
- */
-
-typedef struct
- {
- arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */
- uint16_t fftLenRFFT; /**< length of the real sequence */
- float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */
- } arm_rfft_fast_instance_f32 ;
-
-arm_status arm_rfft_fast_init_f32 (
- arm_rfft_fast_instance_f32 * S,
- uint16_t fftLen);
-
-void arm_rfft_fast_f32(
- arm_rfft_fast_instance_f32 * S,
- float32_t * p, float32_t * pOut,
- uint8_t ifftFlag);
-
- /**
- * @brief Instance structure for the floating-point DCT4/IDCT4 function.
- */
-
- typedef struct
- {
- uint16_t N; /**< length of the DCT4. */
- uint16_t Nby2; /**< half of the length of the DCT4. */
- float32_t normalize; /**< normalizing factor. */
- float32_t *pTwiddle; /**< points to the twiddle factor table. */
- float32_t *pCosFactor; /**< points to the cosFactor table. */
- arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */
- arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */
- } arm_dct4_instance_f32;
-
- /**
- * @brief Initialization function for the floating-point DCT4/IDCT4.
- * @param[in,out] *S points to an instance of floating-point DCT4/IDCT4 structure.
- * @param[in] *S_RFFT points to an instance of floating-point RFFT/RIFFT structure.
- * @param[in] *S_CFFT points to an instance of floating-point CFFT/CIFFT structure.
- * @param[in] N length of the DCT4.
- * @param[in] Nby2 half of the length of the DCT4.
- * @param[in] normalize normalizing factor.
- * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>fftLenReal</code> is not a supported transform length.
- */
-
- arm_status arm_dct4_init_f32(
- arm_dct4_instance_f32 * S,
- arm_rfft_instance_f32 * S_RFFT,
- arm_cfft_radix4_instance_f32 * S_CFFT,
- uint16_t N,
- uint16_t Nby2,
- float32_t normalize);
-
- /**
- * @brief Processing function for the floating-point DCT4/IDCT4.
- * @param[in] *S points to an instance of the floating-point DCT4/IDCT4 structure.
- * @param[in] *pState points to state buffer.
- * @param[in,out] *pInlineBuffer points to the in-place input and output buffer.
- * @return none.
- */
-
- void arm_dct4_f32(
- const arm_dct4_instance_f32 * S,
- float32_t * pState,
- float32_t * pInlineBuffer);
-
- /**
- * @brief Instance structure for the Q31 DCT4/IDCT4 function.
- */
-
- typedef struct
- {
- uint16_t N; /**< length of the DCT4. */
- uint16_t Nby2; /**< half of the length of the DCT4. */
- q31_t normalize; /**< normalizing factor. */
- q31_t *pTwiddle; /**< points to the twiddle factor table. */
- q31_t *pCosFactor; /**< points to the cosFactor table. */
- arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */
- arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */
- } arm_dct4_instance_q31;
-
- /**
- * @brief Initialization function for the Q31 DCT4/IDCT4.
- * @param[in,out] *S points to an instance of Q31 DCT4/IDCT4 structure.
- * @param[in] *S_RFFT points to an instance of Q31 RFFT/RIFFT structure
- * @param[in] *S_CFFT points to an instance of Q31 CFFT/CIFFT structure
- * @param[in] N length of the DCT4.
- * @param[in] Nby2 half of the length of the DCT4.
- * @param[in] normalize normalizing factor.
- * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>N</code> is not a supported transform length.
- */
-
- arm_status arm_dct4_init_q31(
- arm_dct4_instance_q31 * S,
- arm_rfft_instance_q31 * S_RFFT,
- arm_cfft_radix4_instance_q31 * S_CFFT,
- uint16_t N,
- uint16_t Nby2,
- q31_t normalize);
-
- /**
- * @brief Processing function for the Q31 DCT4/IDCT4.
- * @param[in] *S points to an instance of the Q31 DCT4 structure.
- * @param[in] *pState points to state buffer.
- * @param[in,out] *pInlineBuffer points to the in-place input and output buffer.
- * @return none.
- */
-
- void arm_dct4_q31(
- const arm_dct4_instance_q31 * S,
- q31_t * pState,
- q31_t * pInlineBuffer);
-
- /**
- * @brief Instance structure for the Q15 DCT4/IDCT4 function.
- */
-
- typedef struct
- {
- uint16_t N; /**< length of the DCT4. */
- uint16_t Nby2; /**< half of the length of the DCT4. */
- q15_t normalize; /**< normalizing factor. */
- q15_t *pTwiddle; /**< points to the twiddle factor table. */
- q15_t *pCosFactor; /**< points to the cosFactor table. */
- arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */
- arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */
- } arm_dct4_instance_q15;
-
- /**
- * @brief Initialization function for the Q15 DCT4/IDCT4.
- * @param[in,out] *S points to an instance of Q15 DCT4/IDCT4 structure.
- * @param[in] *S_RFFT points to an instance of Q15 RFFT/RIFFT structure.
- * @param[in] *S_CFFT points to an instance of Q15 CFFT/CIFFT structure.
- * @param[in] N length of the DCT4.
- * @param[in] Nby2 half of the length of the DCT4.
- * @param[in] normalize normalizing factor.
- * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>N</code> is not a supported transform length.
- */
-
- arm_status arm_dct4_init_q15(
- arm_dct4_instance_q15 * S,
- arm_rfft_instance_q15 * S_RFFT,
- arm_cfft_radix4_instance_q15 * S_CFFT,
- uint16_t N,
- uint16_t Nby2,
- q15_t normalize);
-
- /**
- * @brief Processing function for the Q15 DCT4/IDCT4.
- * @param[in] *S points to an instance of the Q15 DCT4 structure.
- * @param[in] *pState points to state buffer.
- * @param[in,out] *pInlineBuffer points to the in-place input and output buffer.
- * @return none.
- */
-
- void arm_dct4_q15(
- const arm_dct4_instance_q15 * S,
- q15_t * pState,
- q15_t * pInlineBuffer);
-
- /**
- * @brief Floating-point vector addition.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_add_f32(
- float32_t * pSrcA,
- float32_t * pSrcB,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q7 vector addition.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_add_q7(
- q7_t * pSrcA,
- q7_t * pSrcB,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q15 vector addition.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_add_q15(
- q15_t * pSrcA,
- q15_t * pSrcB,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q31 vector addition.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_add_q31(
- q31_t * pSrcA,
- q31_t * pSrcB,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Floating-point vector subtraction.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_sub_f32(
- float32_t * pSrcA,
- float32_t * pSrcB,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q7 vector subtraction.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_sub_q7(
- q7_t * pSrcA,
- q7_t * pSrcB,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q15 vector subtraction.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_sub_q15(
- q15_t * pSrcA,
- q15_t * pSrcB,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q31 vector subtraction.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_sub_q31(
- q31_t * pSrcA,
- q31_t * pSrcB,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Multiplies a floating-point vector by a scalar.
- * @param[in] *pSrc points to the input vector
- * @param[in] scale scale factor to be applied
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_scale_f32(
- float32_t * pSrc,
- float32_t scale,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Multiplies a Q7 vector by a scalar.
- * @param[in] *pSrc points to the input vector
- * @param[in] scaleFract fractional portion of the scale value
- * @param[in] shift number of bits to shift the result by
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_scale_q7(
- q7_t * pSrc,
- q7_t scaleFract,
- int8_t shift,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Multiplies a Q15 vector by a scalar.
- * @param[in] *pSrc points to the input vector
- * @param[in] scaleFract fractional portion of the scale value
- * @param[in] shift number of bits to shift the result by
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_scale_q15(
- q15_t * pSrc,
- q15_t scaleFract,
- int8_t shift,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Multiplies a Q31 vector by a scalar.
- * @param[in] *pSrc points to the input vector
- * @param[in] scaleFract fractional portion of the scale value
- * @param[in] shift number of bits to shift the result by
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_scale_q31(
- q31_t * pSrc,
- q31_t scaleFract,
- int8_t shift,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q7 vector absolute value.
- * @param[in] *pSrc points to the input buffer
- * @param[out] *pDst points to the output buffer
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_abs_q7(
- q7_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Floating-point vector absolute value.
- * @param[in] *pSrc points to the input buffer
- * @param[out] *pDst points to the output buffer
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_abs_f32(
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q15 vector absolute value.
- * @param[in] *pSrc points to the input buffer
- * @param[out] *pDst points to the output buffer
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_abs_q15(
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Q31 vector absolute value.
- * @param[in] *pSrc points to the input buffer
- * @param[out] *pDst points to the output buffer
- * @param[in] blockSize number of samples in each vector
- * @return none.
- */
-
- void arm_abs_q31(
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Dot product of floating-point vectors.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] blockSize number of samples in each vector
- * @param[out] *result output result returned here
- * @return none.
- */
-
- void arm_dot_prod_f32(
- float32_t * pSrcA,
- float32_t * pSrcB,
- uint32_t blockSize,
- float32_t * result);
-
- /**
- * @brief Dot product of Q7 vectors.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] blockSize number of samples in each vector
- * @param[out] *result output result returned here
- * @return none.
- */
-
- void arm_dot_prod_q7(
- q7_t * pSrcA,
- q7_t * pSrcB,
- uint32_t blockSize,
- q31_t * result);
-
- /**
- * @brief Dot product of Q15 vectors.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] blockSize number of samples in each vector
- * @param[out] *result output result returned here
- * @return none.
- */
-
- void arm_dot_prod_q15(
- q15_t * pSrcA,
- q15_t * pSrcB,
- uint32_t blockSize,
- q63_t * result);
-
- /**
- * @brief Dot product of Q31 vectors.
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] blockSize number of samples in each vector
- * @param[out] *result output result returned here
- * @return none.
- */
-
- void arm_dot_prod_q31(
- q31_t * pSrcA,
- q31_t * pSrcB,
- uint32_t blockSize,
- q63_t * result);
-
- /**
- * @brief Shifts the elements of a Q7 vector a specified number of bits.
- * @param[in] *pSrc points to the input vector
- * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_shift_q7(
- q7_t * pSrc,
- int8_t shiftBits,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Shifts the elements of a Q15 vector a specified number of bits.
- * @param[in] *pSrc points to the input vector
- * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_shift_q15(
- q15_t * pSrc,
- int8_t shiftBits,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Shifts the elements of a Q31 vector a specified number of bits.
- * @param[in] *pSrc points to the input vector
- * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_shift_q31(
- q31_t * pSrc,
- int8_t shiftBits,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Adds a constant offset to a floating-point vector.
- * @param[in] *pSrc points to the input vector
- * @param[in] offset is the offset to be added
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_offset_f32(
- float32_t * pSrc,
- float32_t offset,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Adds a constant offset to a Q7 vector.
- * @param[in] *pSrc points to the input vector
- * @param[in] offset is the offset to be added
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_offset_q7(
- q7_t * pSrc,
- q7_t offset,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Adds a constant offset to a Q15 vector.
- * @param[in] *pSrc points to the input vector
- * @param[in] offset is the offset to be added
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_offset_q15(
- q15_t * pSrc,
- q15_t offset,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Adds a constant offset to a Q31 vector.
- * @param[in] *pSrc points to the input vector
- * @param[in] offset is the offset to be added
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_offset_q31(
- q31_t * pSrc,
- q31_t offset,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Negates the elements of a floating-point vector.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_negate_f32(
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Negates the elements of a Q7 vector.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_negate_q7(
- q7_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Negates the elements of a Q15 vector.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_negate_q15(
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Negates the elements of a Q31 vector.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] blockSize number of samples in the vector
- * @return none.
- */
-
- void arm_negate_q31(
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
- /**
- * @brief Copies the elements of a floating-point vector.
- * @param[in] *pSrc input pointer
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_copy_f32(
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Copies the elements of a Q7 vector.
- * @param[in] *pSrc input pointer
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_copy_q7(
- q7_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Copies the elements of a Q15 vector.
- * @param[in] *pSrc input pointer
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_copy_q15(
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Copies the elements of a Q31 vector.
- * @param[in] *pSrc input pointer
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_copy_q31(
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
- /**
- * @brief Fills a constant value into a floating-point vector.
- * @param[in] value input value to be filled
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_fill_f32(
- float32_t value,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Fills a constant value into a Q7 vector.
- * @param[in] value input value to be filled
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_fill_q7(
- q7_t value,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Fills a constant value into a Q15 vector.
- * @param[in] value input value to be filled
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_fill_q15(
- q15_t value,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Fills a constant value into a Q31 vector.
- * @param[in] value input value to be filled
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_fill_q31(
- q31_t value,
- q31_t * pDst,
- uint32_t blockSize);
-
-/**
- * @brief Convolution of floating-point sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
- * @return none.
- */
-
- void arm_conv_f32(
- float32_t * pSrcA,
- uint32_t srcALen,
- float32_t * pSrcB,
- uint32_t srcBLen,
- float32_t * pDst);
-
-
- /**
- * @brief Convolution of Q15 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
- * @return none.
- */
-
-
- void arm_conv_opt_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
-/**
- * @brief Convolution of Q15 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
- * @return none.
- */
-
- void arm_conv_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst);
-
- /**
- * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @return none.
- */
-
- void arm_conv_fast_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst);
-
- /**
- * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
- * @return none.
- */
-
- void arm_conv_fast_opt_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
-
- /**
- * @brief Convolution of Q31 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @return none.
- */
-
- void arm_conv_q31(
- q31_t * pSrcA,
- uint32_t srcALen,
- q31_t * pSrcB,
- uint32_t srcBLen,
- q31_t * pDst);
-
- /**
- * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @return none.
- */
-
- void arm_conv_fast_q31(
- q31_t * pSrcA,
- uint32_t srcALen,
- q31_t * pSrcB,
- uint32_t srcBLen,
- q31_t * pDst);
-
-
- /**
- * @brief Convolution of Q7 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
- * @return none.
- */
-
- void arm_conv_opt_q7(
- q7_t * pSrcA,
- uint32_t srcALen,
- q7_t * pSrcB,
- uint32_t srcBLen,
- q7_t * pDst,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
-
- /**
- * @brief Convolution of Q7 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
- * @return none.
- */
-
- void arm_conv_q7(
- q7_t * pSrcA,
- uint32_t srcALen,
- q7_t * pSrcB,
- uint32_t srcBLen,
- q7_t * pDst);
-
-
- /**
- * @brief Partial convolution of floating-point sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_f32(
- float32_t * pSrcA,
- uint32_t srcALen,
- float32_t * pSrcB,
- uint32_t srcBLen,
- float32_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints);
-
- /**
- * @brief Partial convolution of Q15 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_opt_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
-/**
- * @brief Partial convolution of Q15 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints);
-
- /**
- * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_fast_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints);
-
-
- /**
- * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_fast_opt_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
- /**
- * @brief Partial convolution of Q31 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_q31(
- q31_t * pSrcA,
- uint32_t srcALen,
- q31_t * pSrcB,
- uint32_t srcBLen,
- q31_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints);
-
-
- /**
- * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_fast_q31(
- q31_t * pSrcA,
- uint32_t srcALen,
- q31_t * pSrcB,
- uint32_t srcBLen,
- q31_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints);
-
-
- /**
- * @brief Partial convolution of Q7 sequences
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_opt_q7(
- q7_t * pSrcA,
- uint32_t srcALen,
- q7_t * pSrcB,
- uint32_t srcBLen,
- q7_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
-/**
- * @brief Partial convolution of Q7 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data
- * @param[in] firstIndex is the first output sample to start with.
- * @param[in] numPoints is the number of output points to be computed.
- * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
- */
-
- arm_status arm_conv_partial_q7(
- q7_t * pSrcA,
- uint32_t srcALen,
- q7_t * pSrcB,
- uint32_t srcBLen,
- q7_t * pDst,
- uint32_t firstIndex,
- uint32_t numPoints);
-
-
-
- /**
- * @brief Instance structure for the Q15 FIR decimator.
- */
-
- typedef struct
- {
- uint8_t M; /**< decimation factor. */
- uint16_t numTaps; /**< number of coefficients in the filter. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- } arm_fir_decimate_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 FIR decimator.
- */
-
- typedef struct
- {
- uint8_t M; /**< decimation factor. */
- uint16_t numTaps; /**< number of coefficients in the filter. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
-
- } arm_fir_decimate_instance_q31;
-
- /**
- * @brief Instance structure for the floating-point FIR decimator.
- */
-
- typedef struct
- {
- uint8_t M; /**< decimation factor. */
- uint16_t numTaps; /**< number of coefficients in the filter. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
-
- } arm_fir_decimate_instance_f32;
-
-
-
- /**
- * @brief Processing function for the floating-point FIR decimator.
- * @param[in] *S points to an instance of the floating-point FIR decimator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of input samples to process per call.
- * @return none
- */
-
- void arm_fir_decimate_f32(
- const arm_fir_decimate_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the floating-point FIR decimator.
- * @param[in,out] *S points to an instance of the floating-point FIR decimator structure.
- * @param[in] numTaps number of coefficients in the filter.
- * @param[in] M decimation factor.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of input samples to process per call.
- * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
- * <code>blockSize</code> is not a multiple of <code>M</code>.
- */
-
- arm_status arm_fir_decimate_init_f32(
- arm_fir_decimate_instance_f32 * S,
- uint16_t numTaps,
- uint8_t M,
- float32_t * pCoeffs,
- float32_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q15 FIR decimator.
- * @param[in] *S points to an instance of the Q15 FIR decimator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of input samples to process per call.
- * @return none
- */
-
- void arm_fir_decimate_q15(
- const arm_fir_decimate_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4.
- * @param[in] *S points to an instance of the Q15 FIR decimator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of input samples to process per call.
- * @return none
- */
-
- void arm_fir_decimate_fast_q15(
- const arm_fir_decimate_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
-
-
- /**
- * @brief Initialization function for the Q15 FIR decimator.
- * @param[in,out] *S points to an instance of the Q15 FIR decimator structure.
- * @param[in] numTaps number of coefficients in the filter.
- * @param[in] M decimation factor.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of input samples to process per call.
- * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
- * <code>blockSize</code> is not a multiple of <code>M</code>.
- */
-
- arm_status arm_fir_decimate_init_q15(
- arm_fir_decimate_instance_q15 * S,
- uint16_t numTaps,
- uint8_t M,
- q15_t * pCoeffs,
- q15_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q31 FIR decimator.
- * @param[in] *S points to an instance of the Q31 FIR decimator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of input samples to process per call.
- * @return none
- */
-
- void arm_fir_decimate_q31(
- const arm_fir_decimate_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4.
- * @param[in] *S points to an instance of the Q31 FIR decimator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of input samples to process per call.
- * @return none
- */
-
- void arm_fir_decimate_fast_q31(
- arm_fir_decimate_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the Q31 FIR decimator.
- * @param[in,out] *S points to an instance of the Q31 FIR decimator structure.
- * @param[in] numTaps number of coefficients in the filter.
- * @param[in] M decimation factor.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of input samples to process per call.
- * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
- * <code>blockSize</code> is not a multiple of <code>M</code>.
- */
-
- arm_status arm_fir_decimate_init_q31(
- arm_fir_decimate_instance_q31 * S,
- uint16_t numTaps,
- uint8_t M,
- q31_t * pCoeffs,
- q31_t * pState,
- uint32_t blockSize);
-
-
-
- /**
- * @brief Instance structure for the Q15 FIR interpolator.
- */
-
- typedef struct
- {
- uint8_t L; /**< upsample factor. */
- uint16_t phaseLength; /**< length of each polyphase filter component. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
- q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */
- } arm_fir_interpolate_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 FIR interpolator.
- */
-
- typedef struct
- {
- uint8_t L; /**< upsample factor. */
- uint16_t phaseLength; /**< length of each polyphase filter component. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
- q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */
- } arm_fir_interpolate_instance_q31;
-
- /**
- * @brief Instance structure for the floating-point FIR interpolator.
- */
-
- typedef struct
- {
- uint8_t L; /**< upsample factor. */
- uint16_t phaseLength; /**< length of each polyphase filter component. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
- float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */
- } arm_fir_interpolate_instance_f32;
-
-
- /**
- * @brief Processing function for the Q15 FIR interpolator.
- * @param[in] *S points to an instance of the Q15 FIR interpolator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_interpolate_q15(
- const arm_fir_interpolate_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the Q15 FIR interpolator.
- * @param[in,out] *S points to an instance of the Q15 FIR interpolator structure.
- * @param[in] L upsample factor.
- * @param[in] numTaps number of filter coefficients in the filter.
- * @param[in] *pCoeffs points to the filter coefficient buffer.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of input samples to process per call.
- * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
- * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
- */
-
- arm_status arm_fir_interpolate_init_q15(
- arm_fir_interpolate_instance_q15 * S,
- uint8_t L,
- uint16_t numTaps,
- q15_t * pCoeffs,
- q15_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q31 FIR interpolator.
- * @param[in] *S points to an instance of the Q15 FIR interpolator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_interpolate_q31(
- const arm_fir_interpolate_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q31 FIR interpolator.
- * @param[in,out] *S points to an instance of the Q31 FIR interpolator structure.
- * @param[in] L upsample factor.
- * @param[in] numTaps number of filter coefficients in the filter.
- * @param[in] *pCoeffs points to the filter coefficient buffer.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of input samples to process per call.
- * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
- * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
- */
-
- arm_status arm_fir_interpolate_init_q31(
- arm_fir_interpolate_instance_q31 * S,
- uint8_t L,
- uint16_t numTaps,
- q31_t * pCoeffs,
- q31_t * pState,
- uint32_t blockSize);
-
-
- /**
- * @brief Processing function for the floating-point FIR interpolator.
- * @param[in] *S points to an instance of the floating-point FIR interpolator structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_interpolate_f32(
- const arm_fir_interpolate_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the floating-point FIR interpolator.
- * @param[in,out] *S points to an instance of the floating-point FIR interpolator structure.
- * @param[in] L upsample factor.
- * @param[in] numTaps number of filter coefficients in the filter.
- * @param[in] *pCoeffs points to the filter coefficient buffer.
- * @param[in] *pState points to the state buffer.
- * @param[in] blockSize number of input samples to process per call.
- * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
- * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
- */
-
- arm_status arm_fir_interpolate_init_f32(
- arm_fir_interpolate_instance_f32 * S,
- uint8_t L,
- uint16_t numTaps,
- float32_t * pCoeffs,
- float32_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Instance structure for the high precision Q31 Biquad cascade filter.
- */
-
- typedef struct
- {
- uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
- q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */
- q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
- uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */
-
- } arm_biquad_cas_df1_32x64_ins_q31;
-
-
- /**
- * @param[in] *S points to an instance of the high precision Q31 Biquad cascade filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cas_df1_32x64_q31(
- const arm_biquad_cas_df1_32x64_ins_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @param[in,out] *S points to an instance of the high precision Q31 Biquad cascade filter structure.
- * @param[in] numStages number of 2nd order stages in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format
- * @return none
- */
-
- void arm_biquad_cas_df1_32x64_init_q31(
- arm_biquad_cas_df1_32x64_ins_q31 * S,
- uint8_t numStages,
- q31_t * pCoeffs,
- q63_t * pState,
- uint8_t postShift);
-
-
-
- /**
- * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter.
- */
-
- typedef struct
- {
- uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
- float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */
- float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
- } arm_biquad_cascade_df2T_instance_f32;
-
-
- /**
- * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter.
- * @param[in] *S points to an instance of the filter data structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_biquad_cascade_df2T_f32(
- const arm_biquad_cascade_df2T_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter.
- * @param[in,out] *S points to an instance of the filter data structure.
- * @param[in] numStages number of 2nd order stages in the filter.
- * @param[in] *pCoeffs points to the filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @return none
- */
-
- void arm_biquad_cascade_df2T_init_f32(
- arm_biquad_cascade_df2T_instance_f32 * S,
- uint8_t numStages,
- float32_t * pCoeffs,
- float32_t * pState);
-
-
-
- /**
- * @brief Instance structure for the Q15 FIR lattice filter.
- */
-
- typedef struct
- {
- uint16_t numStages; /**< number of filter stages. */
- q15_t *pState; /**< points to the state variable array. The array is of length numStages. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
- } arm_fir_lattice_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 FIR lattice filter.
- */
-
- typedef struct
- {
- uint16_t numStages; /**< number of filter stages. */
- q31_t *pState; /**< points to the state variable array. The array is of length numStages. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
- } arm_fir_lattice_instance_q31;
-
- /**
- * @brief Instance structure for the floating-point FIR lattice filter.
- */
-
- typedef struct
- {
- uint16_t numStages; /**< number of filter stages. */
- float32_t *pState; /**< points to the state variable array. The array is of length numStages. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
- } arm_fir_lattice_instance_f32;
-
- /**
- * @brief Initialization function for the Q15 FIR lattice filter.
- * @param[in] *S points to an instance of the Q15 FIR lattice structure.
- * @param[in] numStages number of filter stages.
- * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages.
- * @param[in] *pState points to the state buffer. The array is of length numStages.
- * @return none.
- */
-
- void arm_fir_lattice_init_q15(
- arm_fir_lattice_instance_q15 * S,
- uint16_t numStages,
- q15_t * pCoeffs,
- q15_t * pState);
-
-
- /**
- * @brief Processing function for the Q15 FIR lattice filter.
- * @param[in] *S points to an instance of the Q15 FIR lattice structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
- void arm_fir_lattice_q15(
- const arm_fir_lattice_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q31 FIR lattice filter.
- * @param[in] *S points to an instance of the Q31 FIR lattice structure.
- * @param[in] numStages number of filter stages.
- * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages.
- * @param[in] *pState points to the state buffer. The array is of length numStages.
- * @return none.
- */
-
- void arm_fir_lattice_init_q31(
- arm_fir_lattice_instance_q31 * S,
- uint16_t numStages,
- q31_t * pCoeffs,
- q31_t * pState);
-
-
- /**
- * @brief Processing function for the Q31 FIR lattice filter.
- * @param[in] *S points to an instance of the Q31 FIR lattice structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_fir_lattice_q31(
- const arm_fir_lattice_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
-/**
- * @brief Initialization function for the floating-point FIR lattice filter.
- * @param[in] *S points to an instance of the floating-point FIR lattice structure.
- * @param[in] numStages number of filter stages.
- * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages.
- * @param[in] *pState points to the state buffer. The array is of length numStages.
- * @return none.
- */
-
- void arm_fir_lattice_init_f32(
- arm_fir_lattice_instance_f32 * S,
- uint16_t numStages,
- float32_t * pCoeffs,
- float32_t * pState);
-
- /**
- * @brief Processing function for the floating-point FIR lattice filter.
- * @param[in] *S points to an instance of the floating-point FIR lattice structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_fir_lattice_f32(
- const arm_fir_lattice_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Instance structure for the Q15 IIR lattice filter.
- */
- typedef struct
- {
- uint16_t numStages; /**< number of stages in the filter. */
- q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
- q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
- q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
- } arm_iir_lattice_instance_q15;
-
- /**
- * @brief Instance structure for the Q31 IIR lattice filter.
- */
- typedef struct
- {
- uint16_t numStages; /**< number of stages in the filter. */
- q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
- q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
- q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
- } arm_iir_lattice_instance_q31;
-
- /**
- * @brief Instance structure for the floating-point IIR lattice filter.
- */
- typedef struct
- {
- uint16_t numStages; /**< number of stages in the filter. */
- float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
- float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
- float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
- } arm_iir_lattice_instance_f32;
-
- /**
- * @brief Processing function for the floating-point IIR lattice filter.
- * @param[in] *S points to an instance of the floating-point IIR lattice structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_iir_lattice_f32(
- const arm_iir_lattice_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the floating-point IIR lattice filter.
- * @param[in] *S points to an instance of the floating-point IIR lattice structure.
- * @param[in] numStages number of stages in the filter.
- * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages.
- * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1.
- * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize-1.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_iir_lattice_init_f32(
- arm_iir_lattice_instance_f32 * S,
- uint16_t numStages,
- float32_t * pkCoeffs,
- float32_t * pvCoeffs,
- float32_t * pState,
- uint32_t blockSize);
-
-
- /**
- * @brief Processing function for the Q31 IIR lattice filter.
- * @param[in] *S points to an instance of the Q31 IIR lattice structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_iir_lattice_q31(
- const arm_iir_lattice_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the Q31 IIR lattice filter.
- * @param[in] *S points to an instance of the Q31 IIR lattice structure.
- * @param[in] numStages number of stages in the filter.
- * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages.
- * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1.
- * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_iir_lattice_init_q31(
- arm_iir_lattice_instance_q31 * S,
- uint16_t numStages,
- q31_t * pkCoeffs,
- q31_t * pvCoeffs,
- q31_t * pState,
- uint32_t blockSize);
-
-
- /**
- * @brief Processing function for the Q15 IIR lattice filter.
- * @param[in] *S points to an instance of the Q15 IIR lattice structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_iir_lattice_q15(
- const arm_iir_lattice_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
-
-/**
- * @brief Initialization function for the Q15 IIR lattice filter.
- * @param[in] *S points to an instance of the fixed-point Q15 IIR lattice structure.
- * @param[in] numStages number of stages in the filter.
- * @param[in] *pkCoeffs points to reflection coefficient buffer. The array is of length numStages.
- * @param[in] *pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1.
- * @param[in] *pState points to state buffer. The array is of length numStages+blockSize.
- * @param[in] blockSize number of samples to process per call.
- * @return none.
- */
-
- void arm_iir_lattice_init_q15(
- arm_iir_lattice_instance_q15 * S,
- uint16_t numStages,
- q15_t * pkCoeffs,
- q15_t * pvCoeffs,
- q15_t * pState,
- uint32_t blockSize);
-
- /**
- * @brief Instance structure for the floating-point LMS filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- float32_t mu; /**< step size that controls filter coefficient updates. */
- } arm_lms_instance_f32;
-
- /**
- * @brief Processing function for floating-point LMS filter.
- * @param[in] *S points to an instance of the floating-point LMS filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[in] *pRef points to the block of reference data.
- * @param[out] *pOut points to the block of output data.
- * @param[out] *pErr points to the block of error data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_f32(
- const arm_lms_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pRef,
- float32_t * pOut,
- float32_t * pErr,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for floating-point LMS filter.
- * @param[in] *S points to an instance of the floating-point LMS filter structure.
- * @param[in] numTaps number of filter coefficients.
- * @param[in] *pCoeffs points to the coefficient buffer.
- * @param[in] *pState points to state buffer.
- * @param[in] mu step size that controls filter coefficient updates.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_init_f32(
- arm_lms_instance_f32 * S,
- uint16_t numTaps,
- float32_t * pCoeffs,
- float32_t * pState,
- float32_t mu,
- uint32_t blockSize);
-
- /**
- * @brief Instance structure for the Q15 LMS filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- q15_t mu; /**< step size that controls filter coefficient updates. */
- uint32_t postShift; /**< bit shift applied to coefficients. */
- } arm_lms_instance_q15;
-
-
- /**
- * @brief Initialization function for the Q15 LMS filter.
- * @param[in] *S points to an instance of the Q15 LMS filter structure.
- * @param[in] numTaps number of filter coefficients.
- * @param[in] *pCoeffs points to the coefficient buffer.
- * @param[in] *pState points to the state buffer.
- * @param[in] mu step size that controls filter coefficient updates.
- * @param[in] blockSize number of samples to process.
- * @param[in] postShift bit shift applied to coefficients.
- * @return none.
- */
-
- void arm_lms_init_q15(
- arm_lms_instance_q15 * S,
- uint16_t numTaps,
- q15_t * pCoeffs,
- q15_t * pState,
- q15_t mu,
- uint32_t blockSize,
- uint32_t postShift);
-
- /**
- * @brief Processing function for Q15 LMS filter.
- * @param[in] *S points to an instance of the Q15 LMS filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[in] *pRef points to the block of reference data.
- * @param[out] *pOut points to the block of output data.
- * @param[out] *pErr points to the block of error data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_q15(
- const arm_lms_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pRef,
- q15_t * pOut,
- q15_t * pErr,
- uint32_t blockSize);
-
-
- /**
- * @brief Instance structure for the Q31 LMS filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- q31_t mu; /**< step size that controls filter coefficient updates. */
- uint32_t postShift; /**< bit shift applied to coefficients. */
-
- } arm_lms_instance_q31;
-
- /**
- * @brief Processing function for Q31 LMS filter.
- * @param[in] *S points to an instance of the Q15 LMS filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[in] *pRef points to the block of reference data.
- * @param[out] *pOut points to the block of output data.
- * @param[out] *pErr points to the block of error data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_q31(
- const arm_lms_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pRef,
- q31_t * pOut,
- q31_t * pErr,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for Q31 LMS filter.
- * @param[in] *S points to an instance of the Q31 LMS filter structure.
- * @param[in] numTaps number of filter coefficients.
- * @param[in] *pCoeffs points to coefficient buffer.
- * @param[in] *pState points to state buffer.
- * @param[in] mu step size that controls filter coefficient updates.
- * @param[in] blockSize number of samples to process.
- * @param[in] postShift bit shift applied to coefficients.
- * @return none.
- */
-
- void arm_lms_init_q31(
- arm_lms_instance_q31 * S,
- uint16_t numTaps,
- q31_t * pCoeffs,
- q31_t * pState,
- q31_t mu,
- uint32_t blockSize,
- uint32_t postShift);
-
- /**
- * @brief Instance structure for the floating-point normalized LMS filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- float32_t mu; /**< step size that control filter coefficient updates. */
- float32_t energy; /**< saves previous frame energy. */
- float32_t x0; /**< saves previous input sample. */
- } arm_lms_norm_instance_f32;
-
- /**
- * @brief Processing function for floating-point normalized LMS filter.
- * @param[in] *S points to an instance of the floating-point normalized LMS filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[in] *pRef points to the block of reference data.
- * @param[out] *pOut points to the block of output data.
- * @param[out] *pErr points to the block of error data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_norm_f32(
- arm_lms_norm_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pRef,
- float32_t * pOut,
- float32_t * pErr,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for floating-point normalized LMS filter.
- * @param[in] *S points to an instance of the floating-point LMS filter structure.
- * @param[in] numTaps number of filter coefficients.
- * @param[in] *pCoeffs points to coefficient buffer.
- * @param[in] *pState points to state buffer.
- * @param[in] mu step size that controls filter coefficient updates.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_norm_init_f32(
- arm_lms_norm_instance_f32 * S,
- uint16_t numTaps,
- float32_t * pCoeffs,
- float32_t * pState,
- float32_t mu,
- uint32_t blockSize);
-
-
- /**
- * @brief Instance structure for the Q31 normalized LMS filter.
- */
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- q31_t mu; /**< step size that controls filter coefficient updates. */
- uint8_t postShift; /**< bit shift applied to coefficients. */
- q31_t *recipTable; /**< points to the reciprocal initial value table. */
- q31_t energy; /**< saves previous frame energy. */
- q31_t x0; /**< saves previous input sample. */
- } arm_lms_norm_instance_q31;
-
- /**
- * @brief Processing function for Q31 normalized LMS filter.
- * @param[in] *S points to an instance of the Q31 normalized LMS filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[in] *pRef points to the block of reference data.
- * @param[out] *pOut points to the block of output data.
- * @param[out] *pErr points to the block of error data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_norm_q31(
- arm_lms_norm_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pRef,
- q31_t * pOut,
- q31_t * pErr,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for Q31 normalized LMS filter.
- * @param[in] *S points to an instance of the Q31 normalized LMS filter structure.
- * @param[in] numTaps number of filter coefficients.
- * @param[in] *pCoeffs points to coefficient buffer.
- * @param[in] *pState points to state buffer.
- * @param[in] mu step size that controls filter coefficient updates.
- * @param[in] blockSize number of samples to process.
- * @param[in] postShift bit shift applied to coefficients.
- * @return none.
- */
-
- void arm_lms_norm_init_q31(
- arm_lms_norm_instance_q31 * S,
- uint16_t numTaps,
- q31_t * pCoeffs,
- q31_t * pState,
- q31_t mu,
- uint32_t blockSize,
- uint8_t postShift);
-
- /**
- * @brief Instance structure for the Q15 normalized LMS filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< Number of coefficients in the filter. */
- q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
- q15_t mu; /**< step size that controls filter coefficient updates. */
- uint8_t postShift; /**< bit shift applied to coefficients. */
- q15_t *recipTable; /**< Points to the reciprocal initial value table. */
- q15_t energy; /**< saves previous frame energy. */
- q15_t x0; /**< saves previous input sample. */
- } arm_lms_norm_instance_q15;
-
- /**
- * @brief Processing function for Q15 normalized LMS filter.
- * @param[in] *S points to an instance of the Q15 normalized LMS filter structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[in] *pRef points to the block of reference data.
- * @param[out] *pOut points to the block of output data.
- * @param[out] *pErr points to the block of error data.
- * @param[in] blockSize number of samples to process.
- * @return none.
- */
-
- void arm_lms_norm_q15(
- arm_lms_norm_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pRef,
- q15_t * pOut,
- q15_t * pErr,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for Q15 normalized LMS filter.
- * @param[in] *S points to an instance of the Q15 normalized LMS filter structure.
- * @param[in] numTaps number of filter coefficients.
- * @param[in] *pCoeffs points to coefficient buffer.
- * @param[in] *pState points to state buffer.
- * @param[in] mu step size that controls filter coefficient updates.
- * @param[in] blockSize number of samples to process.
- * @param[in] postShift bit shift applied to coefficients.
- * @return none.
- */
-
- void arm_lms_norm_init_q15(
- arm_lms_norm_instance_q15 * S,
- uint16_t numTaps,
- q15_t * pCoeffs,
- q15_t * pState,
- q15_t mu,
- uint32_t blockSize,
- uint8_t postShift);
-
- /**
- * @brief Correlation of floating-point sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @return none.
- */
-
- void arm_correlate_f32(
- float32_t * pSrcA,
- uint32_t srcALen,
- float32_t * pSrcB,
- uint32_t srcBLen,
- float32_t * pDst);
-
-
- /**
- * @brief Correlation of Q15 sequences
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @return none.
- */
- void arm_correlate_opt_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- q15_t * pScratch);
-
-
- /**
- * @brief Correlation of Q15 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @return none.
- */
-
- void arm_correlate_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst);
-
- /**
- * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @return none.
- */
-
- void arm_correlate_fast_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst);
-
-
-
- /**
- * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @return none.
- */
-
- void arm_correlate_fast_opt_q15(
- q15_t * pSrcA,
- uint32_t srcALen,
- q15_t * pSrcB,
- uint32_t srcBLen,
- q15_t * pDst,
- q15_t * pScratch);
-
- /**
- * @brief Correlation of Q31 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @return none.
- */
-
- void arm_correlate_q31(
- q31_t * pSrcA,
- uint32_t srcALen,
- q31_t * pSrcB,
- uint32_t srcBLen,
- q31_t * pDst);
-
- /**
- * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @return none.
- */
-
- void arm_correlate_fast_q31(
- q31_t * pSrcA,
- uint32_t srcALen,
- q31_t * pSrcB,
- uint32_t srcBLen,
- q31_t * pDst);
-
-
-
- /**
- * @brief Correlation of Q7 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
- * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
- * @return none.
- */
-
- void arm_correlate_opt_q7(
- q7_t * pSrcA,
- uint32_t srcALen,
- q7_t * pSrcB,
- uint32_t srcBLen,
- q7_t * pDst,
- q15_t * pScratch1,
- q15_t * pScratch2);
-
-
- /**
- * @brief Correlation of Q7 sequences.
- * @param[in] *pSrcA points to the first input sequence.
- * @param[in] srcALen length of the first input sequence.
- * @param[in] *pSrcB points to the second input sequence.
- * @param[in] srcBLen length of the second input sequence.
- * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
- * @return none.
- */
-
- void arm_correlate_q7(
- q7_t * pSrcA,
- uint32_t srcALen,
- q7_t * pSrcB,
- uint32_t srcBLen,
- q7_t * pDst);
-
-
- /**
- * @brief Instance structure for the floating-point sparse FIR filter.
- */
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
- float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
- float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
- int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
- } arm_fir_sparse_instance_f32;
-
- /**
- * @brief Instance structure for the Q31 sparse FIR filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
- q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
- q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
- int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
- } arm_fir_sparse_instance_q31;
-
- /**
- * @brief Instance structure for the Q15 sparse FIR filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
- q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
- q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
- int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
- } arm_fir_sparse_instance_q15;
-
- /**
- * @brief Instance structure for the Q7 sparse FIR filter.
- */
-
- typedef struct
- {
- uint16_t numTaps; /**< number of coefficients in the filter. */
- uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
- q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
- q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
- uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
- int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
- } arm_fir_sparse_instance_q7;
-
- /**
- * @brief Processing function for the floating-point sparse FIR filter.
- * @param[in] *S points to an instance of the floating-point sparse FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_sparse_f32(
- arm_fir_sparse_instance_f32 * S,
- float32_t * pSrc,
- float32_t * pDst,
- float32_t * pScratchIn,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the floating-point sparse FIR filter.
- * @param[in,out] *S points to an instance of the floating-point sparse FIR structure.
- * @param[in] numTaps number of nonzero coefficients in the filter.
- * @param[in] *pCoeffs points to the array of filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] *pTapDelay points to the array of offset times.
- * @param[in] maxDelay maximum offset time supported.
- * @param[in] blockSize number of samples that will be processed per block.
- * @return none
- */
-
- void arm_fir_sparse_init_f32(
- arm_fir_sparse_instance_f32 * S,
- uint16_t numTaps,
- float32_t * pCoeffs,
- float32_t * pState,
- int32_t * pTapDelay,
- uint16_t maxDelay,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q31 sparse FIR filter.
- * @param[in] *S points to an instance of the Q31 sparse FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_sparse_q31(
- arm_fir_sparse_instance_q31 * S,
- q31_t * pSrc,
- q31_t * pDst,
- q31_t * pScratchIn,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q31 sparse FIR filter.
- * @param[in,out] *S points to an instance of the Q31 sparse FIR structure.
- * @param[in] numTaps number of nonzero coefficients in the filter.
- * @param[in] *pCoeffs points to the array of filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] *pTapDelay points to the array of offset times.
- * @param[in] maxDelay maximum offset time supported.
- * @param[in] blockSize number of samples that will be processed per block.
- * @return none
- */
-
- void arm_fir_sparse_init_q31(
- arm_fir_sparse_instance_q31 * S,
- uint16_t numTaps,
- q31_t * pCoeffs,
- q31_t * pState,
- int32_t * pTapDelay,
- uint16_t maxDelay,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q15 sparse FIR filter.
- * @param[in] *S points to an instance of the Q15 sparse FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
- * @param[in] *pScratchOut points to a temporary buffer of size blockSize.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_sparse_q15(
- arm_fir_sparse_instance_q15 * S,
- q15_t * pSrc,
- q15_t * pDst,
- q15_t * pScratchIn,
- q31_t * pScratchOut,
- uint32_t blockSize);
-
-
- /**
- * @brief Initialization function for the Q15 sparse FIR filter.
- * @param[in,out] *S points to an instance of the Q15 sparse FIR structure.
- * @param[in] numTaps number of nonzero coefficients in the filter.
- * @param[in] *pCoeffs points to the array of filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] *pTapDelay points to the array of offset times.
- * @param[in] maxDelay maximum offset time supported.
- * @param[in] blockSize number of samples that will be processed per block.
- * @return none
- */
-
- void arm_fir_sparse_init_q15(
- arm_fir_sparse_instance_q15 * S,
- uint16_t numTaps,
- q15_t * pCoeffs,
- q15_t * pState,
- int32_t * pTapDelay,
- uint16_t maxDelay,
- uint32_t blockSize);
-
- /**
- * @brief Processing function for the Q7 sparse FIR filter.
- * @param[in] *S points to an instance of the Q7 sparse FIR structure.
- * @param[in] *pSrc points to the block of input data.
- * @param[out] *pDst points to the block of output data
- * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
- * @param[in] *pScratchOut points to a temporary buffer of size blockSize.
- * @param[in] blockSize number of input samples to process per call.
- * @return none.
- */
-
- void arm_fir_sparse_q7(
- arm_fir_sparse_instance_q7 * S,
- q7_t * pSrc,
- q7_t * pDst,
- q7_t * pScratchIn,
- q31_t * pScratchOut,
- uint32_t blockSize);
-
- /**
- * @brief Initialization function for the Q7 sparse FIR filter.
- * @param[in,out] *S points to an instance of the Q7 sparse FIR structure.
- * @param[in] numTaps number of nonzero coefficients in the filter.
- * @param[in] *pCoeffs points to the array of filter coefficients.
- * @param[in] *pState points to the state buffer.
- * @param[in] *pTapDelay points to the array of offset times.
- * @param[in] maxDelay maximum offset time supported.
- * @param[in] blockSize number of samples that will be processed per block.
- * @return none
- */
-
- void arm_fir_sparse_init_q7(
- arm_fir_sparse_instance_q7 * S,
- uint16_t numTaps,
- q7_t * pCoeffs,
- q7_t * pState,
- int32_t * pTapDelay,
- uint16_t maxDelay,
- uint32_t blockSize);
-
-
- /*
- * @brief Floating-point sin_cos function.
- * @param[in] theta input value in degrees
- * @param[out] *pSinVal points to the processed sine output.
- * @param[out] *pCosVal points to the processed cos output.
- * @return none.
- */
-
- void arm_sin_cos_f32(
- float32_t theta,
- float32_t * pSinVal,
- float32_t * pCcosVal);
-
- /*
- * @brief Q31 sin_cos function.
- * @param[in] theta scaled input value in degrees
- * @param[out] *pSinVal points to the processed sine output.
- * @param[out] *pCosVal points to the processed cosine output.
- * @return none.
- */
-
- void arm_sin_cos_q31(
- q31_t theta,
- q31_t * pSinVal,
- q31_t * pCosVal);
-
-
- /**
- * @brief Floating-point complex conjugate.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] numSamples number of complex samples in each vector
- * @return none.
- */
-
- void arm_cmplx_conj_f32(
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q31 complex conjugate.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] numSamples number of complex samples in each vector
- * @return none.
- */
-
- void arm_cmplx_conj_q31(
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q15 complex conjugate.
- * @param[in] *pSrc points to the input vector
- * @param[out] *pDst points to the output vector
- * @param[in] numSamples number of complex samples in each vector
- * @return none.
- */
-
- void arm_cmplx_conj_q15(
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t numSamples);
-
-
-
- /**
- * @brief Floating-point complex magnitude squared
- * @param[in] *pSrc points to the complex input vector
- * @param[out] *pDst points to the real output vector
- * @param[in] numSamples number of complex samples in the input vector
- * @return none.
- */
-
- void arm_cmplx_mag_squared_f32(
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q31 complex magnitude squared
- * @param[in] *pSrc points to the complex input vector
- * @param[out] *pDst points to the real output vector
- * @param[in] numSamples number of complex samples in the input vector
- * @return none.
- */
-
- void arm_cmplx_mag_squared_q31(
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q15 complex magnitude squared
- * @param[in] *pSrc points to the complex input vector
- * @param[out] *pDst points to the real output vector
- * @param[in] numSamples number of complex samples in the input vector
- * @return none.
- */
-
- void arm_cmplx_mag_squared_q15(
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t numSamples);
-
-
- /**
- * @ingroup groupController
- */
-
- /**
- * @defgroup PID PID Motor Control
- *
- * A Proportional Integral Derivative (PID) controller is a generic feedback control
- * loop mechanism widely used in industrial control systems.
- * A PID controller is the most commonly used type of feedback controller.
- *
- * This set of functions implements (PID) controllers
- * for Q15, Q31, and floating-point data types. The functions operate on a single sample
- * of data and each call to the function returns a single processed value.
- * <code>S</code> points to an instance of the PID control data structure. <code>in</code>
- * is the input sample value. The functions return the output value.
- *
- * \par Algorithm:
- * <pre>
- * y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
- * A0 = Kp + Ki + Kd
- * A1 = (-Kp ) - (2 * Kd )
- * A2 = Kd </pre>
- *
- * \par
- * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant
- *
- * \par
- * \image html PID.gif "Proportional Integral Derivative Controller"
- *
- * \par
- * The PID controller calculates an "error" value as the difference between
- * the measured output and the reference input.
- * The controller attempts to minimize the error by adjusting the process control inputs.
- * The proportional value determines the reaction to the current error,
- * the integral value determines the reaction based on the sum of recent errors,
- * and the derivative value determines the reaction based on the rate at which the error has been changing.
- *
- * \par Instance Structure
- * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure.
- * A separate instance structure must be defined for each PID Controller.
- * There are separate instance structure declarations for each of the 3 supported data types.
- *
- * \par Reset Functions
- * There is also an associated reset function for each data type which clears the state array.
- *
- * \par Initialization Functions
- * There is also an associated initialization function for each data type.
- * The initialization function performs the following operations:
- * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains.
- * - Zeros out the values in the state buffer.
- *
- * \par
- * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function.
- *
- * \par Fixed-Point Behavior
- * Care must be taken when using the fixed-point versions of the PID Controller functions.
- * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered.
- * Refer to the function specific documentation below for usage guidelines.
- */
-
- /**
- * @addtogroup PID
- * @{
- */
-
- /**
- * @brief Process function for the floating-point PID Control.
- * @param[in,out] *S is an instance of the floating-point PID Control structure
- * @param[in] in input sample to process
- * @return out processed output sample.
- */
-
-
- static __INLINE float32_t arm_pid_f32(
- arm_pid_instance_f32 * S,
- float32_t in)
- {
- float32_t out;
-
- /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */
- out = (S->A0 * in) +
- (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]);
-
- /* Update state */
- S->state[1] = S->state[0];
- S->state[0] = in;
- S->state[2] = out;
-
- /* return to application */
- return (out);
-
- }
-
- /**
- * @brief Process function for the Q31 PID Control.
- * @param[in,out] *S points to an instance of the Q31 PID Control structure
- * @param[in] in input sample to process
- * @return out processed output sample.
- *
- * <b>Scaling and Overflow Behavior:</b>
- * \par
- * The function is implemented using an internal 64-bit accumulator.
- * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit.
- * Thus, if the accumulator result overflows it wraps around rather than clip.
- * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions.
- * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format.
- */
-
- static __INLINE q31_t arm_pid_q31(
- arm_pid_instance_q31 * S,
- q31_t in)
- {
- q63_t acc;
- q31_t out;
-
- /* acc = A0 * x[n] */
- acc = (q63_t) S->A0 * in;
-
- /* acc += A1 * x[n-1] */
- acc += (q63_t) S->A1 * S->state[0];
-
- /* acc += A2 * x[n-2] */
- acc += (q63_t) S->A2 * S->state[1];
-
- /* convert output to 1.31 format to add y[n-1] */
- out = (q31_t) (acc >> 31u);
-
- /* out += y[n-1] */
- out += S->state[2];
-
- /* Update state */
- S->state[1] = S->state[0];
- S->state[0] = in;
- S->state[2] = out;
-
- /* return to application */
- return (out);
-
- }
-
- /**
- * @brief Process function for the Q15 PID Control.
- * @param[in,out] *S points to an instance of the Q15 PID Control structure
- * @param[in] in input sample to process
- * @return out processed output sample.
- *
- * <b>Scaling and Overflow Behavior:</b>
- * \par
- * The function is implemented using a 64-bit internal accumulator.
- * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result.
- * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format.
- * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved.
- * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits.
- * Lastly, the accumulator is saturated to yield a result in 1.15 format.
- */
-
- static __INLINE q15_t arm_pid_q15(
- arm_pid_instance_q15 * S,
- q15_t in)
- {
- q63_t acc;
- q15_t out;
-
-#ifndef ARM_MATH_CM0_FAMILY
- __SIMD32_TYPE *vstate;
-
- /* Implementation of PID controller */
-
- /* acc = A0 * x[n] */
- acc = (q31_t) __SMUAD(S->A0, in);
-
- /* acc += A1 * x[n-1] + A2 * x[n-2] */
- vstate = __SIMD32_CONST(S->state);
- acc = __SMLALD(S->A1, (q31_t) *vstate, acc);
-
-#else
- /* acc = A0 * x[n] */
- acc = ((q31_t) S->A0) * in;
-
- /* acc += A1 * x[n-1] + A2 * x[n-2] */
- acc += (q31_t) S->A1 * S->state[0];
- acc += (q31_t) S->A2 * S->state[1];
-
-#endif
-
- /* acc += y[n-1] */
- acc += (q31_t) S->state[2] << 15;
-
- /* saturate the output */
- out = (q15_t) (__SSAT((acc >> 15), 16));
-
- /* Update state */
- S->state[1] = S->state[0];
- S->state[0] = in;
- S->state[2] = out;
-
- /* return to application */
- return (out);
-
- }
-
- /**
- * @} end of PID group
- */
-
-
- /**
- * @brief Floating-point matrix inverse.
- * @param[in] *src points to the instance of the input floating-point matrix structure.
- * @param[out] *dst points to the instance of the output floating-point matrix structure.
- * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match.
- * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR.
- */
-
- arm_status arm_mat_inverse_f32(
- const arm_matrix_instance_f32 * src,
- arm_matrix_instance_f32 * dst);
-
-
-
- /**
- * @ingroup groupController
- */
-
-
- /**
- * @defgroup clarke Vector Clarke Transform
- * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector.
- * Generally the Clarke transform uses three-phase currents <code>Ia, Ib and Ic</code> to calculate currents
- * in the two-phase orthogonal stator axis <code>Ialpha</code> and <code>Ibeta</code>.
- * When <code>Ialpha</code> is superposed with <code>Ia</code> as shown in the figure below
- * \image html clarke.gif Stator current space vector and its components in (a,b).
- * and <code>Ia + Ib + Ic = 0</code>, in this condition <code>Ialpha</code> and <code>Ibeta</code>
- * can be calculated using only <code>Ia</code> and <code>Ib</code>.
- *
- * The function operates on a single sample of data and each call to the function returns the processed output.
- * The library provides separate functions for Q31 and floating-point data types.
- * \par Algorithm
- * \image html clarkeFormula.gif
- * where <code>Ia</code> and <code>Ib</code> are the instantaneous stator phases and
- * <code>pIalpha</code> and <code>pIbeta</code> are the two coordinates of time invariant vector.
- * \par Fixed-Point Behavior
- * Care must be taken when using the Q31 version of the Clarke transform.
- * In particular, the overflow and saturation behavior of the accumulator used must be considered.
- * Refer to the function specific documentation below for usage guidelines.
- */
-
- /**
- * @addtogroup clarke
- * @{
- */
-
- /**
- *
- * @brief Floating-point Clarke transform
- * @param[in] Ia input three-phase coordinate <code>a</code>
- * @param[in] Ib input three-phase coordinate <code>b</code>
- * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
- * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
- * @return none.
- */
-
- static __INLINE void arm_clarke_f32(
- float32_t Ia,
- float32_t Ib,
- float32_t * pIalpha,
- float32_t * pIbeta)
- {
- /* Calculate pIalpha using the equation, pIalpha = Ia */
- *pIalpha = Ia;
-
- /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */
- *pIbeta =
- ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib);
-
- }
-
- /**
- * @brief Clarke transform for Q31 version
- * @param[in] Ia input three-phase coordinate <code>a</code>
- * @param[in] Ib input three-phase coordinate <code>b</code>
- * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
- * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
- * @return none.
- *
- * <b>Scaling and Overflow Behavior:</b>
- * \par
- * The function is implemented using an internal 32-bit accumulator.
- * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
- * There is saturation on the addition, hence there is no risk of overflow.
- */
-
- static __INLINE void arm_clarke_q31(
- q31_t Ia,
- q31_t Ib,
- q31_t * pIalpha,
- q31_t * pIbeta)
- {
- q31_t product1, product2; /* Temporary variables used to store intermediate results */
-
- /* Calculating pIalpha from Ia by equation pIalpha = Ia */
- *pIalpha = Ia;
-
- /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */
- product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30);
-
- /* Intermediate product is calculated by (2/sqrt(3) * Ib) */
- product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30);
-
- /* pIbeta is calculated by adding the intermediate products */
- *pIbeta = __QADD(product1, product2);
- }
-
- /**
- * @} end of clarke group
- */
-
- /**
- * @brief Converts the elements of the Q7 vector to Q31 vector.
- * @param[in] *pSrc input pointer
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_q7_to_q31(
- q7_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
-
-
-
- /**
- * @ingroup groupController
- */
-
- /**
- * @defgroup inv_clarke Vector Inverse Clarke Transform
- * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases.
- *
- * The function operates on a single sample of data and each call to the function returns the processed output.
- * The library provides separate functions for Q31 and floating-point data types.
- * \par Algorithm
- * \image html clarkeInvFormula.gif
- * where <code>pIa</code> and <code>pIb</code> are the instantaneous stator phases and
- * <code>Ialpha</code> and <code>Ibeta</code> are the two coordinates of time invariant vector.
- * \par Fixed-Point Behavior
- * Care must be taken when using the Q31 version of the Clarke transform.
- * In particular, the overflow and saturation behavior of the accumulator used must be considered.
- * Refer to the function specific documentation below for usage guidelines.
- */
-
- /**
- * @addtogroup inv_clarke
- * @{
- */
-
- /**
- * @brief Floating-point Inverse Clarke transform
- * @param[in] Ialpha input two-phase orthogonal vector axis alpha
- * @param[in] Ibeta input two-phase orthogonal vector axis beta
- * @param[out] *pIa points to output three-phase coordinate <code>a</code>
- * @param[out] *pIb points to output three-phase coordinate <code>b</code>
- * @return none.
- */
-
-
- static __INLINE void arm_inv_clarke_f32(
- float32_t Ialpha,
- float32_t Ibeta,
- float32_t * pIa,
- float32_t * pIb)
- {
- /* Calculating pIa from Ialpha by equation pIa = Ialpha */
- *pIa = Ialpha;
-
- /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */
- *pIb = -0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta;
-
- }
-
- /**
- * @brief Inverse Clarke transform for Q31 version
- * @param[in] Ialpha input two-phase orthogonal vector axis alpha
- * @param[in] Ibeta input two-phase orthogonal vector axis beta
- * @param[out] *pIa points to output three-phase coordinate <code>a</code>
- * @param[out] *pIb points to output three-phase coordinate <code>b</code>
- * @return none.
- *
- * <b>Scaling and Overflow Behavior:</b>
- * \par
- * The function is implemented using an internal 32-bit accumulator.
- * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
- * There is saturation on the subtraction, hence there is no risk of overflow.
- */
-
- static __INLINE void arm_inv_clarke_q31(
- q31_t Ialpha,
- q31_t Ibeta,
- q31_t * pIa,
- q31_t * pIb)
- {
- q31_t product1, product2; /* Temporary variables used to store intermediate results */
-
- /* Calculating pIa from Ialpha by equation pIa = Ialpha */
- *pIa = Ialpha;
-
- /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */
- product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31);
-
- /* Intermediate product is calculated by (1/sqrt(3) * pIb) */
- product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31);
-
- /* pIb is calculated by subtracting the products */
- *pIb = __QSUB(product2, product1);
-
- }
-
- /**
- * @} end of inv_clarke group
- */
-
- /**
- * @brief Converts the elements of the Q7 vector to Q15 vector.
- * @param[in] *pSrc input pointer
- * @param[out] *pDst output pointer
- * @param[in] blockSize number of samples to process
- * @return none.
- */
- void arm_q7_to_q15(
- q7_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
-
-
- /**
- * @ingroup groupController
- */
-
- /**
- * @defgroup park Vector Park Transform
- *
- * Forward Park transform converts the input two-coordinate vector to flux and torque components.
- * The Park transform can be used to realize the transformation of the <code>Ialpha</code> and the <code>Ibeta</code> currents
- * from the stationary to the moving reference frame and control the spatial relationship between
- * the stator vector current and rotor flux vector.
- * If we consider the d axis aligned with the rotor flux, the diagram below shows the
- * current vector and the relationship from the two reference frames:
- * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame"
- *
- * The function operates on a single sample of data and each call to the function returns the processed output.
- * The library provides separate functions for Q31 and floating-point data types.
- * \par Algorithm
- * \image html parkFormula.gif
- * where <code>Ialpha</code> and <code>Ibeta</code> are the stator vector components,
- * <code>pId</code> and <code>pIq</code> are rotor vector components and <code>cosVal</code> and <code>sinVal</code> are the
- * cosine and sine values of theta (rotor flux position).
- * \par Fixed-Point Behavior
- * Care must be taken when using the Q31 version of the Park transform.
- * In particular, the overflow and saturation behavior of the accumulator used must be considered.
- * Refer to the function specific documentation below for usage guidelines.
- */
-
- /**
- * @addtogroup park
- * @{
- */
-
- /**
- * @brief Floating-point Park transform
- * @param[in] Ialpha input two-phase vector coordinate alpha
- * @param[in] Ibeta input two-phase vector coordinate beta
- * @param[out] *pId points to output rotor reference frame d
- * @param[out] *pIq points to output rotor reference frame q
- * @param[in] sinVal sine value of rotation angle theta
- * @param[in] cosVal cosine value of rotation angle theta
- * @return none.
- *
- * The function implements the forward Park transform.
- *
- */
-
- static __INLINE void arm_park_f32(
- float32_t Ialpha,
- float32_t Ibeta,
- float32_t * pId,
- float32_t * pIq,
- float32_t sinVal,
- float32_t cosVal)
- {
- /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */
- *pId = Ialpha * cosVal + Ibeta * sinVal;
-
- /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */
- *pIq = -Ialpha * sinVal + Ibeta * cosVal;
-
- }
-
- /**
- * @brief Park transform for Q31 version
- * @param[in] Ialpha input two-phase vector coordinate alpha
- * @param[in] Ibeta input two-phase vector coordinate beta
- * @param[out] *pId points to output rotor reference frame d
- * @param[out] *pIq points to output rotor reference frame q
- * @param[in] sinVal sine value of rotation angle theta
- * @param[in] cosVal cosine value of rotation angle theta
- * @return none.
- *
- * <b>Scaling and Overflow Behavior:</b>
- * \par
- * The function is implemented using an internal 32-bit accumulator.
- * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
- * There is saturation on the addition and subtraction, hence there is no risk of overflow.
- */
-
-
- static __INLINE void arm_park_q31(
- q31_t Ialpha,
- q31_t Ibeta,
- q31_t * pId,
- q31_t * pIq,
- q31_t sinVal,
- q31_t cosVal)
- {
- q31_t product1, product2; /* Temporary variables used to store intermediate results */
- q31_t product3, product4; /* Temporary variables used to store intermediate results */
-
- /* Intermediate product is calculated by (Ialpha * cosVal) */
- product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31);
-
- /* Intermediate product is calculated by (Ibeta * sinVal) */
- product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31);
-
-
- /* Intermediate product is calculated by (Ialpha * sinVal) */
- product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31);
-
- /* Intermediate product is calculated by (Ibeta * cosVal) */
- product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31);
-
- /* Calculate pId by adding the two intermediate products 1 and 2 */
- *pId = __QADD(product1, product2);
-
- /* Calculate pIq by subtracting the two intermediate products 3 from 4 */
- *pIq = __QSUB(product4, product3);
- }
-
- /**
- * @} end of park group
- */
-
- /**
- * @brief Converts the elements of the Q7 vector to floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q7_to_float(
- q7_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @ingroup groupController
- */
-
- /**
- * @defgroup inv_park Vector Inverse Park transform
- * Inverse Park transform converts the input flux and torque components to two-coordinate vector.
- *
- * The function operates on a single sample of data and each call to the function returns the processed output.
- * The library provides separate functions for Q31 and floating-point data types.
- * \par Algorithm
- * \image html parkInvFormula.gif
- * where <code>pIalpha</code> and <code>pIbeta</code> are the stator vector components,
- * <code>Id</code> and <code>Iq</code> are rotor vector components and <code>cosVal</code> and <code>sinVal</code> are the
- * cosine and sine values of theta (rotor flux position).
- * \par Fixed-Point Behavior
- * Care must be taken when using the Q31 version of the Park transform.
- * In particular, the overflow and saturation behavior of the accumulator used must be considered.
- * Refer to the function specific documentation below for usage guidelines.
- */
-
- /**
- * @addtogroup inv_park
- * @{
- */
-
- /**
- * @brief Floating-point Inverse Park transform
- * @param[in] Id input coordinate of rotor reference frame d
- * @param[in] Iq input coordinate of rotor reference frame q
- * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
- * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
- * @param[in] sinVal sine value of rotation angle theta
- * @param[in] cosVal cosine value of rotation angle theta
- * @return none.
- */
-
- static __INLINE void arm_inv_park_f32(
- float32_t Id,
- float32_t Iq,
- float32_t * pIalpha,
- float32_t * pIbeta,
- float32_t sinVal,
- float32_t cosVal)
- {
- /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */
- *pIalpha = Id * cosVal - Iq * sinVal;
-
- /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */
- *pIbeta = Id * sinVal + Iq * cosVal;
-
- }
-
-
- /**
- * @brief Inverse Park transform for Q31 version
- * @param[in] Id input coordinate of rotor reference frame d
- * @param[in] Iq input coordinate of rotor reference frame q
- * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
- * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
- * @param[in] sinVal sine value of rotation angle theta
- * @param[in] cosVal cosine value of rotation angle theta
- * @return none.
- *
- * <b>Scaling and Overflow Behavior:</b>
- * \par
- * The function is implemented using an internal 32-bit accumulator.
- * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
- * There is saturation on the addition, hence there is no risk of overflow.
- */
-
-
- static __INLINE void arm_inv_park_q31(
- q31_t Id,
- q31_t Iq,
- q31_t * pIalpha,
- q31_t * pIbeta,
- q31_t sinVal,
- q31_t cosVal)
- {
- q31_t product1, product2; /* Temporary variables used to store intermediate results */
- q31_t product3, product4; /* Temporary variables used to store intermediate results */
-
- /* Intermediate product is calculated by (Id * cosVal) */
- product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31);
-
- /* Intermediate product is calculated by (Iq * sinVal) */
- product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31);
-
-
- /* Intermediate product is calculated by (Id * sinVal) */
- product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31);
-
- /* Intermediate product is calculated by (Iq * cosVal) */
- product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31);
-
- /* Calculate pIalpha by using the two intermediate products 1 and 2 */
- *pIalpha = __QSUB(product1, product2);
-
- /* Calculate pIbeta by using the two intermediate products 3 and 4 */
- *pIbeta = __QADD(product4, product3);
-
- }
-
- /**
- * @} end of Inverse park group
- */
-
-
- /**
- * @brief Converts the elements of the Q31 vector to floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q31_to_float(
- q31_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
- /**
- * @ingroup groupInterpolation
- */
-
- /**
- * @defgroup LinearInterpolate Linear Interpolation
- *
- * Linear interpolation is a method of curve fitting using linear polynomials.
- * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line
- *
- * \par
- * \image html LinearInterp.gif "Linear interpolation"
- *
- * \par
- * A Linear Interpolate function calculates an output value(y), for the input(x)
- * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values)
- *
- * \par Algorithm:
- * <pre>
- * y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
- * where x0, x1 are nearest values of input x
- * y0, y1 are nearest values to output y
- * </pre>
- *
- * \par
- * This set of functions implements Linear interpolation process
- * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single
- * sample of data and each call to the function returns a single processed value.
- * <code>S</code> points to an instance of the Linear Interpolate function data structure.
- * <code>x</code> is the input sample value. The functions returns the output value.
- *
- * \par
- * if x is outside of the table boundary, Linear interpolation returns first value of the table
- * if x is below input range and returns last value of table if x is above range.
- */
-
- /**
- * @addtogroup LinearInterpolate
- * @{
- */
-
- /**
- * @brief Process function for the floating-point Linear Interpolation Function.
- * @param[in,out] *S is an instance of the floating-point Linear Interpolation structure
- * @param[in] x input sample to process
- * @return y processed output sample.
- *
- */
-
- static __INLINE float32_t arm_linear_interp_f32(
- arm_linear_interp_instance_f32 * S,
- float32_t x)
- {
-
- float32_t y;
- float32_t x0, x1; /* Nearest input values */
- float32_t y0, y1; /* Nearest output values */
- float32_t xSpacing = S->xSpacing; /* spacing between input values */
- int32_t i; /* Index variable */
- float32_t *pYData = S->pYData; /* pointer to output table */
-
- /* Calculation of index */
- i = (int32_t) ((x - S->x1) / xSpacing);
-
- if(i < 0)
- {
- /* Iniatilize output for below specified range as least output value of table */
- y = pYData[0];
- }
- else if((uint32_t)i >= S->nValues)
- {
- /* Iniatilize output for above specified range as last output value of table */
- y = pYData[S->nValues - 1];
- }
- else
- {
- /* Calculation of nearest input values */
- x0 = S->x1 + i * xSpacing;
- x1 = S->x1 + (i + 1) * xSpacing;
-
- /* Read of nearest output values */
- y0 = pYData[i];
- y1 = pYData[i + 1];
-
- /* Calculation of output */
- y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0));
-
- }
-
- /* returns output value */
- return (y);
- }
-
- /**
- *
- * @brief Process function for the Q31 Linear Interpolation Function.
- * @param[in] *pYData pointer to Q31 Linear Interpolation table
- * @param[in] x input sample to process
- * @param[in] nValues number of table values
- * @return y processed output sample.
- *
- * \par
- * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
- * This function can support maximum of table size 2^12.
- *
- */
-
-
- static __INLINE q31_t arm_linear_interp_q31(
- q31_t * pYData,
- q31_t x,
- uint32_t nValues)
- {
- q31_t y; /* output */
- q31_t y0, y1; /* Nearest output values */
- q31_t fract; /* fractional part */
- int32_t index; /* Index to read nearest output values */
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- index = ((x & 0xFFF00000) >> 20);
-
- if(index >= (int32_t)(nValues - 1))
- {
- return (pYData[nValues - 1]);
- }
- else if(index < 0)
- {
- return (pYData[0]);
- }
- else
- {
-
- /* 20 bits for the fractional part */
- /* shift left by 11 to keep fract in 1.31 format */
- fract = (x & 0x000FFFFF) << 11;
-
- /* Read two nearest output values from the index in 1.31(q31) format */
- y0 = pYData[index];
- y1 = pYData[index + 1u];
-
- /* Calculation of y0 * (1-fract) and y is in 2.30 format */
- y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32));
-
- /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */
- y += ((q31_t) (((q63_t) y1 * fract) >> 32));
-
- /* Convert y to 1.31 format */
- return (y << 1u);
-
- }
-
- }
-
- /**
- *
- * @brief Process function for the Q15 Linear Interpolation Function.
- * @param[in] *pYData pointer to Q15 Linear Interpolation table
- * @param[in] x input sample to process
- * @param[in] nValues number of table values
- * @return y processed output sample.
- *
- * \par
- * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
- * This function can support maximum of table size 2^12.
- *
- */
-
-
- static __INLINE q15_t arm_linear_interp_q15(
- q15_t * pYData,
- q31_t x,
- uint32_t nValues)
- {
- q63_t y; /* output */
- q15_t y0, y1; /* Nearest output values */
- q31_t fract; /* fractional part */
- int32_t index; /* Index to read nearest output values */
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- index = ((x & 0xFFF00000) >> 20u);
-
- if(index >= (int32_t)(nValues - 1))
- {
- return (pYData[nValues - 1]);
- }
- else if(index < 0)
- {
- return (pYData[0]);
- }
- else
- {
- /* 20 bits for the fractional part */
- /* fract is in 12.20 format */
- fract = (x & 0x000FFFFF);
-
- /* Read two nearest output values from the index */
- y0 = pYData[index];
- y1 = pYData[index + 1u];
-
- /* Calculation of y0 * (1-fract) and y is in 13.35 format */
- y = ((q63_t) y0 * (0xFFFFF - fract));
-
- /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */
- y += ((q63_t) y1 * (fract));
-
- /* convert y to 1.15 format */
- return (y >> 20);
- }
-
-
- }
-
- /**
- *
- * @brief Process function for the Q7 Linear Interpolation Function.
- * @param[in] *pYData pointer to Q7 Linear Interpolation table
- * @param[in] x input sample to process
- * @param[in] nValues number of table values
- * @return y processed output sample.
- *
- * \par
- * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
- * This function can support maximum of table size 2^12.
- */
-
-
- static __INLINE q7_t arm_linear_interp_q7(
- q7_t * pYData,
- q31_t x,
- uint32_t nValues)
- {
- q31_t y; /* output */
- q7_t y0, y1; /* Nearest output values */
- q31_t fract; /* fractional part */
- uint32_t index; /* Index to read nearest output values */
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- if (x < 0)
- {
- return (pYData[0]);
- }
- index = (x >> 20) & 0xfff;
-
-
- if(index >= (nValues - 1))
- {
- return (pYData[nValues - 1]);
- }
- else
- {
-
- /* 20 bits for the fractional part */
- /* fract is in 12.20 format */
- fract = (x & 0x000FFFFF);
-
- /* Read two nearest output values from the index and are in 1.7(q7) format */
- y0 = pYData[index];
- y1 = pYData[index + 1u];
-
- /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */
- y = ((y0 * (0xFFFFF - fract)));
-
- /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */
- y += (y1 * fract);
-
- /* convert y to 1.7(q7) format */
- return (y >> 20u);
-
- }
-
- }
- /**
- * @} end of LinearInterpolate group
- */
-
- /**
- * @brief Fast approximation to the trigonometric sine function for floating-point data.
- * @param[in] x input value in radians.
- * @return sin(x).
- */
-
- float32_t arm_sin_f32(
- float32_t x);
-
- /**
- * @brief Fast approximation to the trigonometric sine function for Q31 data.
- * @param[in] x Scaled input value in radians.
- * @return sin(x).
- */
-
- q31_t arm_sin_q31(
- q31_t x);
-
- /**
- * @brief Fast approximation to the trigonometric sine function for Q15 data.
- * @param[in] x Scaled input value in radians.
- * @return sin(x).
- */
-
- q15_t arm_sin_q15(
- q15_t x);
-
- /**
- * @brief Fast approximation to the trigonometric cosine function for floating-point data.
- * @param[in] x input value in radians.
- * @return cos(x).
- */
-
- float32_t arm_cos_f32(
- float32_t x);
-
- /**
- * @brief Fast approximation to the trigonometric cosine function for Q31 data.
- * @param[in] x Scaled input value in radians.
- * @return cos(x).
- */
-
- q31_t arm_cos_q31(
- q31_t x);
-
- /**
- * @brief Fast approximation to the trigonometric cosine function for Q15 data.
- * @param[in] x Scaled input value in radians.
- * @return cos(x).
- */
-
- q15_t arm_cos_q15(
- q15_t x);
-
-
- /**
- * @ingroup groupFastMath
- */
-
-
- /**
- * @defgroup SQRT Square Root
- *
- * Computes the square root of a number.
- * There are separate functions for Q15, Q31, and floating-point data types.
- * The square root function is computed using the Newton-Raphson algorithm.
- * This is an iterative algorithm of the form:
- * <pre>
- * x1 = x0 - f(x0)/f'(x0)
- * </pre>
- * where <code>x1</code> is the current estimate,
- * <code>x0</code> is the previous estimate, and
- * <code>f'(x0)</code> is the derivative of <code>f()</code> evaluated at <code>x0</code>.
- * For the square root function, the algorithm reduces to:
- * <pre>
- * x0 = in/2 [initial guess]
- * x1 = 1/2 * ( x0 + in / x0) [each iteration]
- * </pre>
- */
-
-
- /**
- * @addtogroup SQRT
- * @{
- */
-
- /**
- * @brief Floating-point square root function.
- * @param[in] in input value.
- * @param[out] *pOut square root of input value.
- * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
- * <code>in</code> is negative value and returns zero output for negative values.
- */
-
- static __INLINE arm_status arm_sqrt_f32(
- float32_t in,
- float32_t * pOut)
- {
- if(in > 0)
- {
-
-// #if __FPU_USED
-#if (__FPU_USED == 1) && defined ( __CC_ARM )
- *pOut = __sqrtf(in);
-#else
- *pOut = sqrtf(in);
-#endif
-
- return (ARM_MATH_SUCCESS);
- }
- else
- {
- *pOut = 0.0f;
- return (ARM_MATH_ARGUMENT_ERROR);
- }
-
- }
-
-
- /**
- * @brief Q31 square root function.
- * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF.
- * @param[out] *pOut square root of input value.
- * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
- * <code>in</code> is negative value and returns zero output for negative values.
- */
- arm_status arm_sqrt_q31(
- q31_t in,
- q31_t * pOut);
-
- /**
- * @brief Q15 square root function.
- * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF.
- * @param[out] *pOut square root of input value.
- * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
- * <code>in</code> is negative value and returns zero output for negative values.
- */
- arm_status arm_sqrt_q15(
- q15_t in,
- q15_t * pOut);
-
- /**
- * @} end of SQRT group
- */
-
-
-
-
-
-
- /**
- * @brief floating-point Circular write function.
- */
-
- static __INLINE void arm_circularWrite_f32(
- int32_t * circBuffer,
- int32_t L,
- uint16_t * writeOffset,
- int32_t bufferInc,
- const int32_t * src,
- int32_t srcInc,
- uint32_t blockSize)
- {
- uint32_t i = 0u;
- int32_t wOffset;
-
- /* Copy the value of Index pointer that points
- * to the current location where the input samples to be copied */
- wOffset = *writeOffset;
-
- /* Loop over the blockSize */
- i = blockSize;
-
- while(i > 0u)
- {
- /* copy the input sample to the circular buffer */
- circBuffer[wOffset] = *src;
-
- /* Update the input pointer */
- src += srcInc;
-
- /* Circularly update wOffset. Watch out for positive and negative value */
- wOffset += bufferInc;
- if(wOffset >= L)
- wOffset -= L;
-
- /* Decrement the loop counter */
- i--;
- }
-
- /* Update the index pointer */
- *writeOffset = wOffset;
- }
-
-
-
- /**
- * @brief floating-point Circular Read function.
- */
- static __INLINE void arm_circularRead_f32(
- int32_t * circBuffer,
- int32_t L,
- int32_t * readOffset,
- int32_t bufferInc,
- int32_t * dst,
- int32_t * dst_base,
- int32_t dst_length,
- int32_t dstInc,
- uint32_t blockSize)
- {
- uint32_t i = 0u;
- int32_t rOffset, dst_end;
-
- /* Copy the value of Index pointer that points
- * to the current location from where the input samples to be read */
- rOffset = *readOffset;
- dst_end = (int32_t) (dst_base + dst_length);
-
- /* Loop over the blockSize */
- i = blockSize;
-
- while(i > 0u)
- {
- /* copy the sample from the circular buffer to the destination buffer */
- *dst = circBuffer[rOffset];
-
- /* Update the input pointer */
- dst += dstInc;
-
- if(dst == (int32_t *) dst_end)
- {
- dst = dst_base;
- }
-
- /* Circularly update rOffset. Watch out for positive and negative value */
- rOffset += bufferInc;
-
- if(rOffset >= L)
- {
- rOffset -= L;
- }
-
- /* Decrement the loop counter */
- i--;
- }
-
- /* Update the index pointer */
- *readOffset = rOffset;
- }
-
- /**
- * @brief Q15 Circular write function.
- */
-
- static __INLINE void arm_circularWrite_q15(
- q15_t * circBuffer,
- int32_t L,
- uint16_t * writeOffset,
- int32_t bufferInc,
- const q15_t * src,
- int32_t srcInc,
- uint32_t blockSize)
- {
- uint32_t i = 0u;
- int32_t wOffset;
-
- /* Copy the value of Index pointer that points
- * to the current location where the input samples to be copied */
- wOffset = *writeOffset;
-
- /* Loop over the blockSize */
- i = blockSize;
-
- while(i > 0u)
- {
- /* copy the input sample to the circular buffer */
- circBuffer[wOffset] = *src;
-
- /* Update the input pointer */
- src += srcInc;
-
- /* Circularly update wOffset. Watch out for positive and negative value */
- wOffset += bufferInc;
- if(wOffset >= L)
- wOffset -= L;
-
- /* Decrement the loop counter */
- i--;
- }
-
- /* Update the index pointer */
- *writeOffset = wOffset;
- }
-
-
-
- /**
- * @brief Q15 Circular Read function.
- */
- static __INLINE void arm_circularRead_q15(
- q15_t * circBuffer,
- int32_t L,
- int32_t * readOffset,
- int32_t bufferInc,
- q15_t * dst,
- q15_t * dst_base,
- int32_t dst_length,
- int32_t dstInc,
- uint32_t blockSize)
- {
- uint32_t i = 0;
- int32_t rOffset, dst_end;
-
- /* Copy the value of Index pointer that points
- * to the current location from where the input samples to be read */
- rOffset = *readOffset;
-
- dst_end = (int32_t) (dst_base + dst_length);
-
- /* Loop over the blockSize */
- i = blockSize;
-
- while(i > 0u)
- {
- /* copy the sample from the circular buffer to the destination buffer */
- *dst = circBuffer[rOffset];
-
- /* Update the input pointer */
- dst += dstInc;
-
- if(dst == (q15_t *) dst_end)
- {
- dst = dst_base;
- }
-
- /* Circularly update wOffset. Watch out for positive and negative value */
- rOffset += bufferInc;
-
- if(rOffset >= L)
- {
- rOffset -= L;
- }
-
- /* Decrement the loop counter */
- i--;
- }
-
- /* Update the index pointer */
- *readOffset = rOffset;
- }
-
-
- /**
- * @brief Q7 Circular write function.
- */
-
- static __INLINE void arm_circularWrite_q7(
- q7_t * circBuffer,
- int32_t L,
- uint16_t * writeOffset,
- int32_t bufferInc,
- const q7_t * src,
- int32_t srcInc,
- uint32_t blockSize)
- {
- uint32_t i = 0u;
- int32_t wOffset;
-
- /* Copy the value of Index pointer that points
- * to the current location where the input samples to be copied */
- wOffset = *writeOffset;
-
- /* Loop over the blockSize */
- i = blockSize;
-
- while(i > 0u)
- {
- /* copy the input sample to the circular buffer */
- circBuffer[wOffset] = *src;
-
- /* Update the input pointer */
- src += srcInc;
-
- /* Circularly update wOffset. Watch out for positive and negative value */
- wOffset += bufferInc;
- if(wOffset >= L)
- wOffset -= L;
-
- /* Decrement the loop counter */
- i--;
- }
-
- /* Update the index pointer */
- *writeOffset = wOffset;
- }
-
-
-
- /**
- * @brief Q7 Circular Read function.
- */
- static __INLINE void arm_circularRead_q7(
- q7_t * circBuffer,
- int32_t L,
- int32_t * readOffset,
- int32_t bufferInc,
- q7_t * dst,
- q7_t * dst_base,
- int32_t dst_length,
- int32_t dstInc,
- uint32_t blockSize)
- {
- uint32_t i = 0;
- int32_t rOffset, dst_end;
-
- /* Copy the value of Index pointer that points
- * to the current location from where the input samples to be read */
- rOffset = *readOffset;
-
- dst_end = (int32_t) (dst_base + dst_length);
-
- /* Loop over the blockSize */
- i = blockSize;
-
- while(i > 0u)
- {
- /* copy the sample from the circular buffer to the destination buffer */
- *dst = circBuffer[rOffset];
-
- /* Update the input pointer */
- dst += dstInc;
-
- if(dst == (q7_t *) dst_end)
- {
- dst = dst_base;
- }
-
- /* Circularly update rOffset. Watch out for positive and negative value */
- rOffset += bufferInc;
-
- if(rOffset >= L)
- {
- rOffset -= L;
- }
-
- /* Decrement the loop counter */
- i--;
- }
-
- /* Update the index pointer */
- *readOffset = rOffset;
- }
-
-
- /**
- * @brief Sum of the squares of the elements of a Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_power_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q63_t * pResult);
-
- /**
- * @brief Sum of the squares of the elements of a floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_power_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult);
-
- /**
- * @brief Sum of the squares of the elements of a Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_power_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q63_t * pResult);
-
- /**
- * @brief Sum of the squares of the elements of a Q7 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_power_q7(
- q7_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult);
-
- /**
- * @brief Mean value of a Q7 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_mean_q7(
- q7_t * pSrc,
- uint32_t blockSize,
- q7_t * pResult);
-
- /**
- * @brief Mean value of a Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
- void arm_mean_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q15_t * pResult);
-
- /**
- * @brief Mean value of a Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
- void arm_mean_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult);
-
- /**
- * @brief Mean value of a floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
- void arm_mean_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult);
-
- /**
- * @brief Variance of the elements of a floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_var_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult);
-
- /**
- * @brief Variance of the elements of a Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_var_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q63_t * pResult);
-
- /**
- * @brief Variance of the elements of a Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_var_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult);
-
- /**
- * @brief Root Mean Square of the elements of a floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_rms_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult);
-
- /**
- * @brief Root Mean Square of the elements of a Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_rms_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult);
-
- /**
- * @brief Root Mean Square of the elements of a Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_rms_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q15_t * pResult);
-
- /**
- * @brief Standard deviation of the elements of a floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_std_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult);
-
- /**
- * @brief Standard deviation of the elements of a Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_std_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult);
-
- /**
- * @brief Standard deviation of the elements of a Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output value.
- * @return none.
- */
-
- void arm_std_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q15_t * pResult);
-
- /**
- * @brief Floating-point complex magnitude
- * @param[in] *pSrc points to the complex input vector
- * @param[out] *pDst points to the real output vector
- * @param[in] numSamples number of complex samples in the input vector
- * @return none.
- */
-
- void arm_cmplx_mag_f32(
- float32_t * pSrc,
- float32_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q31 complex magnitude
- * @param[in] *pSrc points to the complex input vector
- * @param[out] *pDst points to the real output vector
- * @param[in] numSamples number of complex samples in the input vector
- * @return none.
- */
-
- void arm_cmplx_mag_q31(
- q31_t * pSrc,
- q31_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q15 complex magnitude
- * @param[in] *pSrc points to the complex input vector
- * @param[out] *pDst points to the real output vector
- * @param[in] numSamples number of complex samples in the input vector
- * @return none.
- */
-
- void arm_cmplx_mag_q15(
- q15_t * pSrc,
- q15_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q15 complex dot product
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] numSamples number of complex samples in each vector
- * @param[out] *realResult real part of the result returned here
- * @param[out] *imagResult imaginary part of the result returned here
- * @return none.
- */
-
- void arm_cmplx_dot_prod_q15(
- q15_t * pSrcA,
- q15_t * pSrcB,
- uint32_t numSamples,
- q31_t * realResult,
- q31_t * imagResult);
-
- /**
- * @brief Q31 complex dot product
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] numSamples number of complex samples in each vector
- * @param[out] *realResult real part of the result returned here
- * @param[out] *imagResult imaginary part of the result returned here
- * @return none.
- */
-
- void arm_cmplx_dot_prod_q31(
- q31_t * pSrcA,
- q31_t * pSrcB,
- uint32_t numSamples,
- q63_t * realResult,
- q63_t * imagResult);
-
- /**
- * @brief Floating-point complex dot product
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[in] numSamples number of complex samples in each vector
- * @param[out] *realResult real part of the result returned here
- * @param[out] *imagResult imaginary part of the result returned here
- * @return none.
- */
-
- void arm_cmplx_dot_prod_f32(
- float32_t * pSrcA,
- float32_t * pSrcB,
- uint32_t numSamples,
- float32_t * realResult,
- float32_t * imagResult);
-
- /**
- * @brief Q15 complex-by-real multiplication
- * @param[in] *pSrcCmplx points to the complex input vector
- * @param[in] *pSrcReal points to the real input vector
- * @param[out] *pCmplxDst points to the complex output vector
- * @param[in] numSamples number of samples in each vector
- * @return none.
- */
-
- void arm_cmplx_mult_real_q15(
- q15_t * pSrcCmplx,
- q15_t * pSrcReal,
- q15_t * pCmplxDst,
- uint32_t numSamples);
-
- /**
- * @brief Q31 complex-by-real multiplication
- * @param[in] *pSrcCmplx points to the complex input vector
- * @param[in] *pSrcReal points to the real input vector
- * @param[out] *pCmplxDst points to the complex output vector
- * @param[in] numSamples number of samples in each vector
- * @return none.
- */
-
- void arm_cmplx_mult_real_q31(
- q31_t * pSrcCmplx,
- q31_t * pSrcReal,
- q31_t * pCmplxDst,
- uint32_t numSamples);
-
- /**
- * @brief Floating-point complex-by-real multiplication
- * @param[in] *pSrcCmplx points to the complex input vector
- * @param[in] *pSrcReal points to the real input vector
- * @param[out] *pCmplxDst points to the complex output vector
- * @param[in] numSamples number of samples in each vector
- * @return none.
- */
-
- void arm_cmplx_mult_real_f32(
- float32_t * pSrcCmplx,
- float32_t * pSrcReal,
- float32_t * pCmplxDst,
- uint32_t numSamples);
-
- /**
- * @brief Minimum value of a Q7 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *result is output pointer
- * @param[in] index is the array index of the minimum value in the input buffer.
- * @return none.
- */
-
- void arm_min_q7(
- q7_t * pSrc,
- uint32_t blockSize,
- q7_t * result,
- uint32_t * index);
-
- /**
- * @brief Minimum value of a Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output pointer
- * @param[in] *pIndex is the array index of the minimum value in the input buffer.
- * @return none.
- */
-
- void arm_min_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q15_t * pResult,
- uint32_t * pIndex);
-
- /**
- * @brief Minimum value of a Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output pointer
- * @param[out] *pIndex is the array index of the minimum value in the input buffer.
- * @return none.
- */
- void arm_min_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult,
- uint32_t * pIndex);
-
- /**
- * @brief Minimum value of a floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[in] blockSize is the number of samples to process
- * @param[out] *pResult is output pointer
- * @param[out] *pIndex is the array index of the minimum value in the input buffer.
- * @return none.
- */
-
- void arm_min_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult,
- uint32_t * pIndex);
-
-/**
- * @brief Maximum value of a Q7 vector.
- * @param[in] *pSrc points to the input buffer
- * @param[in] blockSize length of the input vector
- * @param[out] *pResult maximum value returned here
- * @param[out] *pIndex index of maximum value returned here
- * @return none.
- */
-
- void arm_max_q7(
- q7_t * pSrc,
- uint32_t blockSize,
- q7_t * pResult,
- uint32_t * pIndex);
-
-/**
- * @brief Maximum value of a Q15 vector.
- * @param[in] *pSrc points to the input buffer
- * @param[in] blockSize length of the input vector
- * @param[out] *pResult maximum value returned here
- * @param[out] *pIndex index of maximum value returned here
- * @return none.
- */
-
- void arm_max_q15(
- q15_t * pSrc,
- uint32_t blockSize,
- q15_t * pResult,
- uint32_t * pIndex);
-
-/**
- * @brief Maximum value of a Q31 vector.
- * @param[in] *pSrc points to the input buffer
- * @param[in] blockSize length of the input vector
- * @param[out] *pResult maximum value returned here
- * @param[out] *pIndex index of maximum value returned here
- * @return none.
- */
-
- void arm_max_q31(
- q31_t * pSrc,
- uint32_t blockSize,
- q31_t * pResult,
- uint32_t * pIndex);
-
-/**
- * @brief Maximum value of a floating-point vector.
- * @param[in] *pSrc points to the input buffer
- * @param[in] blockSize length of the input vector
- * @param[out] *pResult maximum value returned here
- * @param[out] *pIndex index of maximum value returned here
- * @return none.
- */
-
- void arm_max_f32(
- float32_t * pSrc,
- uint32_t blockSize,
- float32_t * pResult,
- uint32_t * pIndex);
-
- /**
- * @brief Q15 complex-by-complex multiplication
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] numSamples number of complex samples in each vector
- * @return none.
- */
-
- void arm_cmplx_mult_cmplx_q15(
- q15_t * pSrcA,
- q15_t * pSrcB,
- q15_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Q31 complex-by-complex multiplication
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] numSamples number of complex samples in each vector
- * @return none.
- */
-
- void arm_cmplx_mult_cmplx_q31(
- q31_t * pSrcA,
- q31_t * pSrcB,
- q31_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Floating-point complex-by-complex multiplication
- * @param[in] *pSrcA points to the first input vector
- * @param[in] *pSrcB points to the second input vector
- * @param[out] *pDst points to the output vector
- * @param[in] numSamples number of complex samples in each vector
- * @return none.
- */
-
- void arm_cmplx_mult_cmplx_f32(
- float32_t * pSrcA,
- float32_t * pSrcB,
- float32_t * pDst,
- uint32_t numSamples);
-
- /**
- * @brief Converts the elements of the floating-point vector to Q31 vector.
- * @param[in] *pSrc points to the floating-point input vector
- * @param[out] *pDst points to the Q31 output vector
- * @param[in] blockSize length of the input vector
- * @return none.
- */
- void arm_float_to_q31(
- float32_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Converts the elements of the floating-point vector to Q15 vector.
- * @param[in] *pSrc points to the floating-point input vector
- * @param[out] *pDst points to the Q15 output vector
- * @param[in] blockSize length of the input vector
- * @return none
- */
- void arm_float_to_q15(
- float32_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Converts the elements of the floating-point vector to Q7 vector.
- * @param[in] *pSrc points to the floating-point input vector
- * @param[out] *pDst points to the Q7 output vector
- * @param[in] blockSize length of the input vector
- * @return none
- */
- void arm_float_to_q7(
- float32_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Converts the elements of the Q31 vector to Q15 vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q31_to_q15(
- q31_t * pSrc,
- q15_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Converts the elements of the Q31 vector to Q7 vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q31_to_q7(
- q31_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
- /**
- * @brief Converts the elements of the Q15 vector to floating-point vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q15_to_float(
- q15_t * pSrc,
- float32_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Converts the elements of the Q15 vector to Q31 vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q15_to_q31(
- q15_t * pSrc,
- q31_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @brief Converts the elements of the Q15 vector to Q7 vector.
- * @param[in] *pSrc is input pointer
- * @param[out] *pDst is output pointer
- * @param[in] blockSize is the number of samples to process
- * @return none.
- */
- void arm_q15_to_q7(
- q15_t * pSrc,
- q7_t * pDst,
- uint32_t blockSize);
-
-
- /**
- * @ingroup groupInterpolation
- */
-
- /**
- * @defgroup BilinearInterpolate Bilinear Interpolation
- *
- * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid.
- * The underlying function <code>f(x, y)</code> is sampled on a regular grid and the interpolation process
- * determines values between the grid points.
- * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension.
- * Bilinear interpolation is often used in image processing to rescale images.
- * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types.
- *
- * <b>Algorithm</b>
- * \par
- * The instance structure used by the bilinear interpolation functions describes a two dimensional data table.
- * For floating-point, the instance structure is defined as:
- * <pre>
- * typedef struct
- * {
- * uint16_t numRows;
- * uint16_t numCols;
- * float32_t *pData;
- * } arm_bilinear_interp_instance_f32;
- * </pre>
- *
- * \par
- * where <code>numRows</code> specifies the number of rows in the table;
- * <code>numCols</code> specifies the number of columns in the table;
- * and <code>pData</code> points to an array of size <code>numRows*numCols</code> values.
- * The data table <code>pTable</code> is organized in row order and the supplied data values fall on integer indexes.
- * That is, table element (x,y) is located at <code>pTable[x + y*numCols]</code> where x and y are integers.
- *
- * \par
- * Let <code>(x, y)</code> specify the desired interpolation point. Then define:
- * <pre>
- * XF = floor(x)
- * YF = floor(y)
- * </pre>
- * \par
- * The interpolated output point is computed as:
- * <pre>
- * f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
- * + f(XF+1, YF) * (x-XF)*(1-(y-YF))
- * + f(XF, YF+1) * (1-(x-XF))*(y-YF)
- * + f(XF+1, YF+1) * (x-XF)*(y-YF)
- * </pre>
- * Note that the coordinates (x, y) contain integer and fractional components.
- * The integer components specify which portion of the table to use while the
- * fractional components control the interpolation processor.
- *
- * \par
- * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output.
- */
-
- /**
- * @addtogroup BilinearInterpolate
- * @{
- */
-
- /**
- *
- * @brief Floating-point bilinear interpolation.
- * @param[in,out] *S points to an instance of the interpolation structure.
- * @param[in] X interpolation coordinate.
- * @param[in] Y interpolation coordinate.
- * @return out interpolated value.
- */
-
-
- static __INLINE float32_t arm_bilinear_interp_f32(
- const arm_bilinear_interp_instance_f32 * S,
- float32_t X,
- float32_t Y)
- {
- float32_t out;
- float32_t f00, f01, f10, f11;
- float32_t *pData = S->pData;
- int32_t xIndex, yIndex, index;
- float32_t xdiff, ydiff;
- float32_t b1, b2, b3, b4;
-
- xIndex = (int32_t) X;
- yIndex = (int32_t) Y;
-
- /* Care taken for table outside boundary */
- /* Returns zero output when values are outside table boundary */
- if(xIndex < 0 || xIndex > (S->numRows - 1) || yIndex < 0
- || yIndex > (S->numCols - 1))
- {
- return (0);
- }
-
- /* Calculation of index for two nearest points in X-direction */
- index = (xIndex - 1) + (yIndex - 1) * S->numCols;
-
-
- /* Read two nearest points in X-direction */
- f00 = pData[index];
- f01 = pData[index + 1];
-
- /* Calculation of index for two nearest points in Y-direction */
- index = (xIndex - 1) + (yIndex) * S->numCols;
-
-
- /* Read two nearest points in Y-direction */
- f10 = pData[index];
- f11 = pData[index + 1];
-
- /* Calculation of intermediate values */
- b1 = f00;
- b2 = f01 - f00;
- b3 = f10 - f00;
- b4 = f00 - f01 - f10 + f11;
-
- /* Calculation of fractional part in X */
- xdiff = X - xIndex;
-
- /* Calculation of fractional part in Y */
- ydiff = Y - yIndex;
-
- /* Calculation of bi-linear interpolated output */
- out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff;
-
- /* return to application */
- return (out);
-
- }
-
- /**
- *
- * @brief Q31 bilinear interpolation.
- * @param[in,out] *S points to an instance of the interpolation structure.
- * @param[in] X interpolation coordinate in 12.20 format.
- * @param[in] Y interpolation coordinate in 12.20 format.
- * @return out interpolated value.
- */
-
- static __INLINE q31_t arm_bilinear_interp_q31(
- arm_bilinear_interp_instance_q31 * S,
- q31_t X,
- q31_t Y)
- {
- q31_t out; /* Temporary output */
- q31_t acc = 0; /* output */
- q31_t xfract, yfract; /* X, Y fractional parts */
- q31_t x1, x2, y1, y2; /* Nearest output values */
- int32_t rI, cI; /* Row and column indices */
- q31_t *pYData = S->pData; /* pointer to output table values */
- uint32_t nCols = S->numCols; /* num of rows */
-
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- rI = ((X & 0xFFF00000) >> 20u);
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- cI = ((Y & 0xFFF00000) >> 20u);
-
- /* Care taken for table outside boundary */
- /* Returns zero output when values are outside table boundary */
- if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
- {
- return (0);
- }
-
- /* 20 bits for the fractional part */
- /* shift left xfract by 11 to keep 1.31 format */
- xfract = (X & 0x000FFFFF) << 11u;
-
- /* Read two nearest output values from the index */
- x1 = pYData[(rI) + nCols * (cI)];
- x2 = pYData[(rI) + nCols * (cI) + 1u];
-
- /* 20 bits for the fractional part */
- /* shift left yfract by 11 to keep 1.31 format */
- yfract = (Y & 0x000FFFFF) << 11u;
-
- /* Read two nearest output values from the index */
- y1 = pYData[(rI) + nCols * (cI + 1)];
- y2 = pYData[(rI) + nCols * (cI + 1) + 1u];
-
- /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */
- out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32));
- acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32));
-
- /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */
- out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32));
- acc += ((q31_t) ((q63_t) out * (xfract) >> 32));
-
- /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */
- out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32));
- acc += ((q31_t) ((q63_t) out * (yfract) >> 32));
-
- /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */
- out = ((q31_t) ((q63_t) y2 * (xfract) >> 32));
- acc += ((q31_t) ((q63_t) out * (yfract) >> 32));
-
- /* Convert acc to 1.31(q31) format */
- return (acc << 2u);
-
- }
-
- /**
- * @brief Q15 bilinear interpolation.
- * @param[in,out] *S points to an instance of the interpolation structure.
- * @param[in] X interpolation coordinate in 12.20 format.
- * @param[in] Y interpolation coordinate in 12.20 format.
- * @return out interpolated value.
- */
-
- static __INLINE q15_t arm_bilinear_interp_q15(
- arm_bilinear_interp_instance_q15 * S,
- q31_t X,
- q31_t Y)
- {
- q63_t acc = 0; /* output */
- q31_t out; /* Temporary output */
- q15_t x1, x2, y1, y2; /* Nearest output values */
- q31_t xfract, yfract; /* X, Y fractional parts */
- int32_t rI, cI; /* Row and column indices */
- q15_t *pYData = S->pData; /* pointer to output table values */
- uint32_t nCols = S->numCols; /* num of rows */
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- rI = ((X & 0xFFF00000) >> 20);
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- cI = ((Y & 0xFFF00000) >> 20);
-
- /* Care taken for table outside boundary */
- /* Returns zero output when values are outside table boundary */
- if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
- {
- return (0);
- }
-
- /* 20 bits for the fractional part */
- /* xfract should be in 12.20 format */
- xfract = (X & 0x000FFFFF);
-
- /* Read two nearest output values from the index */
- x1 = pYData[(rI) + nCols * (cI)];
- x2 = pYData[(rI) + nCols * (cI) + 1u];
-
-
- /* 20 bits for the fractional part */
- /* yfract should be in 12.20 format */
- yfract = (Y & 0x000FFFFF);
-
- /* Read two nearest output values from the index */
- y1 = pYData[(rI) + nCols * (cI + 1)];
- y2 = pYData[(rI) + nCols * (cI + 1) + 1u];
-
- /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */
-
- /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */
- /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */
- out = (q31_t) (((q63_t) x1 * (0xFFFFF - xfract)) >> 4u);
- acc = ((q63_t) out * (0xFFFFF - yfract));
-
- /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */
- out = (q31_t) (((q63_t) x2 * (0xFFFFF - yfract)) >> 4u);
- acc += ((q63_t) out * (xfract));
-
- /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */
- out = (q31_t) (((q63_t) y1 * (0xFFFFF - xfract)) >> 4u);
- acc += ((q63_t) out * (yfract));
-
- /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */
- out = (q31_t) (((q63_t) y2 * (xfract)) >> 4u);
- acc += ((q63_t) out * (yfract));
-
- /* acc is in 13.51 format and down shift acc by 36 times */
- /* Convert out to 1.15 format */
- return (acc >> 36);
-
- }
-
- /**
- * @brief Q7 bilinear interpolation.
- * @param[in,out] *S points to an instance of the interpolation structure.
- * @param[in] X interpolation coordinate in 12.20 format.
- * @param[in] Y interpolation coordinate in 12.20 format.
- * @return out interpolated value.
- */
-
- static __INLINE q7_t arm_bilinear_interp_q7(
- arm_bilinear_interp_instance_q7 * S,
- q31_t X,
- q31_t Y)
- {
- q63_t acc = 0; /* output */
- q31_t out; /* Temporary output */
- q31_t xfract, yfract; /* X, Y fractional parts */
- q7_t x1, x2, y1, y2; /* Nearest output values */
- int32_t rI, cI; /* Row and column indices */
- q7_t *pYData = S->pData; /* pointer to output table values */
- uint32_t nCols = S->numCols; /* num of rows */
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- rI = ((X & 0xFFF00000) >> 20);
-
- /* Input is in 12.20 format */
- /* 12 bits for the table index */
- /* Index value calculation */
- cI = ((Y & 0xFFF00000) >> 20);
-
- /* Care taken for table outside boundary */
- /* Returns zero output when values are outside table boundary */
- if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
- {
- return (0);
- }
-
- /* 20 bits for the fractional part */
- /* xfract should be in 12.20 format */
- xfract = (X & 0x000FFFFF);
-
- /* Read two nearest output values from the index */
- x1 = pYData[(rI) + nCols * (cI)];
- x2 = pYData[(rI) + nCols * (cI) + 1u];
-
-
- /* 20 bits for the fractional part */
- /* yfract should be in 12.20 format */
- yfract = (Y & 0x000FFFFF);
-
- /* Read two nearest output values from the index */
- y1 = pYData[(rI) + nCols * (cI + 1)];
- y2 = pYData[(rI) + nCols * (cI + 1) + 1u];
-
- /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */
- out = ((x1 * (0xFFFFF - xfract)));
- acc = (((q63_t) out * (0xFFFFF - yfract)));
-
- /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */
- out = ((x2 * (0xFFFFF - yfract)));
- acc += (((q63_t) out * (xfract)));
-
- /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */
- out = ((y1 * (0xFFFFF - xfract)));
- acc += (((q63_t) out * (yfract)));
-
- /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */
- out = ((y2 * (yfract)));
- acc += (((q63_t) out * (xfract)));
-
- /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */
- return (acc >> 40);
-
- }
-
- /**
- * @} end of BilinearInterpolate group
- */
-
-
-#if defined ( __CC_ARM ) //Keil
-//SMMLAR
- #define multAcc_32x32_keep32_R(a, x, y) \
- a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32)
-
-//SMMLSR
- #define multSub_32x32_keep32_R(a, x, y) \
- a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32)
-
-//SMMULR
- #define mult_32x32_keep32_R(a, x, y) \
- a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32)
-
-//Enter low optimization region - place directly above function definition
- #define LOW_OPTIMIZATION_ENTER \
- _Pragma ("push") \
- _Pragma ("O1")
-
-//Exit low optimization region - place directly after end of function definition
- #define LOW_OPTIMIZATION_EXIT \
- _Pragma ("pop")
-
-//Enter low optimization region - place directly above function definition
- #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
-
-//Exit low optimization region - place directly after end of function definition
- #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
-
-#elif defined(__ICCARM__) //IAR
- //SMMLA
- #define multAcc_32x32_keep32_R(a, x, y) \
- a += (q31_t) (((q63_t) x * y) >> 32)
-
- //SMMLS
- #define multSub_32x32_keep32_R(a, x, y) \
- a -= (q31_t) (((q63_t) x * y) >> 32)
-
-//SMMUL
- #define mult_32x32_keep32_R(a, x, y) \
- a = (q31_t) (((q63_t) x * y ) >> 32)
-
-//Enter low optimization region - place directly above function definition
- #define LOW_OPTIMIZATION_ENTER \
- _Pragma ("optimize=low")
-
-//Exit low optimization region - place directly after end of function definition
- #define LOW_OPTIMIZATION_EXIT
-
-//Enter low optimization region - place directly above function definition
- #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \
- _Pragma ("optimize=low")
-
-//Exit low optimization region - place directly after end of function definition
- #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
-
-#elif defined(__GNUC__)
- //SMMLA
- #define multAcc_32x32_keep32_R(a, x, y) \
- a += (q31_t) (((q63_t) x * y) >> 32)
-
- //SMMLS
- #define multSub_32x32_keep32_R(a, x, y) \
- a -= (q31_t) (((q63_t) x * y) >> 32)
-
-//SMMUL
- #define mult_32x32_keep32_R(a, x, y) \
- a = (q31_t) (((q63_t) x * y ) >> 32)
-
- #define LOW_OPTIMIZATION_ENTER __attribute__(( optimize("-O1") ))
-
- #define LOW_OPTIMIZATION_EXIT
-
- #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
-
- #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
-
-#endif
-
-
-
-
-
-#ifdef __cplusplus
-}
-#endif
-
-
-#endif /* _ARM_MATH_H */
-
-
-/**
- *
- * End of file.
- */
diff --git a/src/modules/mathlib/CMSIS/Include/core_cm3.h b/src/modules/mathlib/CMSIS/Include/core_cm3.h
deleted file mode 100644
index 8ac6dc078..000000000
--- a/src/modules/mathlib/CMSIS/Include/core_cm3.h
+++ /dev/null
@@ -1,1627 +0,0 @@
-/**************************************************************************//**
- * @file core_cm3.h
- * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File
- * @version V3.20
- * @date 25. February 2013
- *
- * @note
- *
- ******************************************************************************/
-/* Copyright (c) 2009 - 2013 ARM LIMITED
-
- All rights reserved.
- Redistribution and use in source and binary forms, with or without
- modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - 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.
- - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- ---------------------------------------------------------------------------*/
-
-
-#if defined ( __ICCARM__ )
- #pragma system_include /* treat file as system include file for MISRA check */
-#endif
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-#ifndef __CORE_CM3_H_GENERIC
-#define __CORE_CM3_H_GENERIC
-
-/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
- CMSIS violates the following MISRA-C:2004 rules:
-
- \li Required Rule 8.5, object/function definition in header file.<br>
- Function definitions in header files are used to allow 'inlining'.
-
- \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
- Unions are used for effective representation of core registers.
-
- \li Advisory Rule 19.7, Function-like macro defined.<br>
- Function-like macros are used to allow more efficient code.
- */
-
-
-/*******************************************************************************
- * CMSIS definitions
- ******************************************************************************/
-/** \ingroup Cortex_M3
- @{
- */
-
-/* CMSIS CM3 definitions */
-#define __CM3_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */
-#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
-#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | \
- __CM3_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */
-
-#define __CORTEX_M (0x03) /*!< Cortex-M Core */
-
-
-#if defined ( __CC_ARM )
- #define __ASM __asm /*!< asm keyword for ARM Compiler */
- #define __INLINE __inline /*!< inline keyword for ARM Compiler */
- #define __STATIC_INLINE static __inline
-
-#elif defined ( __ICCARM__ )
- #define __ASM __asm /*!< asm keyword for IAR Compiler */
- #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */
- #define __STATIC_INLINE static inline
-
-#elif defined ( __TMS470__ )
- #define __ASM __asm /*!< asm keyword for TI CCS Compiler */
- #define __STATIC_INLINE static inline
-
-#elif defined ( __GNUC__ )
- #define __ASM __asm /*!< asm keyword for GNU Compiler */
- #define __INLINE inline /*!< inline keyword for GNU Compiler */
- #define __STATIC_INLINE static inline
-
-#elif defined ( __TASKING__ )
- #define __ASM __asm /*!< asm keyword for TASKING Compiler */
- #define __INLINE inline /*!< inline keyword for TASKING Compiler */
- #define __STATIC_INLINE static inline
-
-#endif
-
-/** __FPU_USED indicates whether an FPU is used or not. This core does not support an FPU at all
-*/
-#define __FPU_USED 0
-
-#if defined ( __CC_ARM )
- #if defined __TARGET_FPU_VFP
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #endif
-
-#elif defined ( __ICCARM__ )
- #if defined __ARMVFP__
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #endif
-
-#elif defined ( __TMS470__ )
- #if defined __TI__VFP_SUPPORT____
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #endif
-
-#elif defined ( __GNUC__ )
- #if defined (__VFP_FP__) && !defined(__SOFTFP__)
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #endif
-
-#elif defined ( __TASKING__ )
- #if defined __FPU_VFP__
- #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #endif
-#endif
-
-#include <stdint.h> /* standard types definitions */
-#include "core_cmInstr.h" /* Core Instruction Access */
-#include "core_cmFunc.h" /* Core Function Access */
-
-#endif /* __CORE_CM3_H_GENERIC */
-
-#ifndef __CMSIS_GENERIC
-
-#ifndef __CORE_CM3_H_DEPENDANT
-#define __CORE_CM3_H_DEPENDANT
-
-/* check device defines and use defaults */
-#if defined __CHECK_DEVICE_DEFINES
- #ifndef __CM3_REV
- #define __CM3_REV 0x0200
- #warning "__CM3_REV not defined in device header file; using default!"
- #endif
-
- #ifndef __MPU_PRESENT
- #define __MPU_PRESENT 0
- #warning "__MPU_PRESENT not defined in device header file; using default!"
- #endif
-
- #ifndef __NVIC_PRIO_BITS
- #define __NVIC_PRIO_BITS 4
- #warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
- #endif
-
- #ifndef __Vendor_SysTickConfig
- #define __Vendor_SysTickConfig 0
- #warning "__Vendor_SysTickConfig not defined in device header file; using default!"
- #endif
-#endif
-
-/* IO definitions (access restrictions to peripheral registers) */
-/**
- \defgroup CMSIS_glob_defs CMSIS Global Defines
-
- <strong>IO Type Qualifiers</strong> are used
- \li to specify the access to peripheral variables.
- \li for automatic generation of peripheral register debug information.
-*/
-#ifdef __cplusplus
- #define __I volatile /*!< Defines 'read only' permissions */
-#else
- #define __I volatile const /*!< Defines 'read only' permissions */
-#endif
-#define __O volatile /*!< Defines 'write only' permissions */
-#define __IO volatile /*!< Defines 'read / write' permissions */
-
-/*@} end of group Cortex_M3 */
-
-
-
-/*******************************************************************************
- * Register Abstraction
- Core Register contain:
- - Core Register
- - Core NVIC Register
- - Core SCB Register
- - Core SysTick Register
- - Core Debug Register
- - Core MPU Register
- ******************************************************************************/
-/** \defgroup CMSIS_core_register Defines and Type Definitions
- \brief Type definitions and defines for Cortex-M processor based devices.
-*/
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_CORE Status and Control Registers
- \brief Core Register type definitions.
- @{
- */
-
-/** \brief Union type to access the Application Program Status Register (APSR).
- */
-typedef union
-{
- struct
- {
-#if (__CORTEX_M != 0x04)
- uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */
-#else
- uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */
- uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
- uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */
-#endif
- uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
- uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
- uint32_t C:1; /*!< bit: 29 Carry condition code flag */
- uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
- uint32_t N:1; /*!< bit: 31 Negative condition code flag */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} APSR_Type;
-
-
-/** \brief Union type to access the Interrupt Program Status Register (IPSR).
- */
-typedef union
-{
- struct
- {
- uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
- uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} IPSR_Type;
-
-
-/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR).
- */
-typedef union
-{
- struct
- {
- uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
-#if (__CORTEX_M != 0x04)
- uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */
-#else
- uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */
- uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
- uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */
-#endif
- uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
- uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */
- uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
- uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
- uint32_t C:1; /*!< bit: 29 Carry condition code flag */
- uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
- uint32_t N:1; /*!< bit: 31 Negative condition code flag */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} xPSR_Type;
-
-
-/** \brief Union type to access the Control Registers (CONTROL).
- */
-typedef union
-{
- struct
- {
- uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
- uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
- uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */
- uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} CONTROL_Type;
-
-/*@} end of group CMSIS_CORE */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
- \brief Type definitions for the NVIC Registers
- @{
- */
-
-/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
- */
-typedef struct
-{
- __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
- uint32_t RESERVED0[24];
- __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
- uint32_t RSERVED1[24];
- __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
- uint32_t RESERVED2[24];
- __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
- uint32_t RESERVED3[24];
- __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
- uint32_t RESERVED4[56];
- __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
- uint32_t RESERVED5[644];
- __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
-} NVIC_Type;
-
-/* Software Triggered Interrupt Register Definitions */
-#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */
-#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */
-
-/*@} end of group CMSIS_NVIC */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_SCB System Control Block (SCB)
- \brief Type definitions for the System Control Block Registers
- @{
- */
-
-/** \brief Structure type to access the System Control Block (SCB).
- */
-typedef struct
-{
- __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
- __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
- __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
- __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
- __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
- __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
- __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
- __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
- __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
- __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
- __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
- __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
- __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
- __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
- __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
- __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
- __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
- __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
- __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
- uint32_t RESERVED0[5];
- __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
-} SCB_Type;
-
-/* SCB CPUID Register Definitions */
-#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */
-#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
-
-#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */
-#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
-
-#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */
-#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
-
-#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */
-#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
-
-#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */
-#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */
-
-/* SCB Interrupt Control State Register Definitions */
-#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */
-#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
-
-#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */
-#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
-
-#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */
-#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
-
-#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */
-#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
-
-#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */
-#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
-
-#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */
-#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
-
-#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */
-#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
-
-#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */
-#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
-
-#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */
-#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */
-
-#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */
-#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */
-
-/* SCB Vector Table Offset Register Definitions */
-#if (__CM3_REV < 0x0201) /* core r2p1 */
-#define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */
-#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */
-
-#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
-#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
-#else
-#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
-#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
-#endif
-
-/* SCB Application Interrupt and Reset Control Register Definitions */
-#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
-#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
-
-#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */
-#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
-
-#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */
-#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
-
-#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
-#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
-
-#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */
-#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
-
-#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */
-#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
-
-#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */
-#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */
-
-/* SCB System Control Register Definitions */
-#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */
-#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
-
-#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */
-#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
-
-#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */
-#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
-
-/* SCB Configuration Control Register Definitions */
-#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */
-#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
-
-#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */
-#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
-
-#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */
-#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */
-
-#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */
-#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
-
-#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */
-#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
-
-#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */
-#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */
-
-/* SCB System Handler Control and State Register Definitions */
-#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */
-#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
-
-#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */
-#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
-
-#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */
-#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
-
-#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */
-#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
-
-#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */
-#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
-
-#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */
-#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
-
-#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */
-#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
-
-#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */
-#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
-
-#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */
-#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
-
-#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */
-#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
-
-#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */
-#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
-
-#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */
-#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
-
-#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */
-#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
-
-#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */
-#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */
-
-/* SCB Configurable Fault Status Registers Definitions */
-#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */
-#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
-
-#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */
-#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
-
-#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */
-#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
-
-/* SCB Hard Fault Status Registers Definitions */
-#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */
-#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
-
-#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */
-#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
-
-#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */
-#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
-
-/* SCB Debug Fault Status Register Definitions */
-#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */
-#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
-
-#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */
-#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
-
-#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */
-#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
-
-#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */
-#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
-
-#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */
-#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */
-
-/*@} end of group CMSIS_SCB */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
- \brief Type definitions for the System Control and ID Register not in the SCB
- @{
- */
-
-/** \brief Structure type to access the System Control and ID Register not in the SCB.
- */
-typedef struct
-{
- uint32_t RESERVED0[1];
- __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
-#if ((defined __CM3_REV) && (__CM3_REV >= 0x200))
- __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
-#else
- uint32_t RESERVED1[1];
-#endif
-} SCnSCB_Type;
-
-/* Interrupt Controller Type Register Definitions */
-#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */
-#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */
-
-/* Auxiliary Control Register Definitions */
-
-#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */
-#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */
-
-#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */
-#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */
-
-#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */
-#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */
-
-/*@} end of group CMSIS_SCnotSCB */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_SysTick System Tick Timer (SysTick)
- \brief Type definitions for the System Timer Registers.
- @{
- */
-
-/** \brief Structure type to access the System Timer (SysTick).
- */
-typedef struct
-{
- __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
- __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
- __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
- __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
-} SysTick_Type;
-
-/* SysTick Control / Status Register Definitions */
-#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */
-#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
-
-#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */
-#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
-
-#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */
-#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
-
-#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */
-#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */
-
-/* SysTick Reload Register Definitions */
-#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */
-#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */
-
-/* SysTick Current Register Definitions */
-#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */
-#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */
-
-/* SysTick Calibration Register Definitions */
-#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */
-#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
-
-#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */
-#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
-
-#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */
-#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */
-
-/*@} end of group CMSIS_SysTick */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM)
- \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
- @{
- */
-
-/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
- */
-typedef struct
-{
- __O union
- {
- __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
- __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
- __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
- } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
- uint32_t RESERVED0[864];
- __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
- uint32_t RESERVED1[15];
- __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
- uint32_t RESERVED2[15];
- __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
- uint32_t RESERVED3[29];
- __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
- __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
- __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
- uint32_t RESERVED4[43];
- __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
- __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
- uint32_t RESERVED5[6];
- __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
- __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
- __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
- __I uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
- __I uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
- __I uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
- __I uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
- __I uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
- __I uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
- __I uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
- __I uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
- __I uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
-} ITM_Type;
-
-/* ITM Trace Privilege Register Definitions */
-#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */
-#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */
-
-/* ITM Trace Control Register Definitions */
-#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */
-#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
-
-#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */
-#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */
-
-#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */
-#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
-
-#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */
-#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
-
-#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */
-#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
-
-#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */
-#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
-
-#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */
-#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
-
-#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */
-#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
-
-#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */
-#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */
-
-/* ITM Integration Write Register Definitions */
-#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */
-#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */
-
-/* ITM Integration Read Register Definitions */
-#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */
-#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */
-
-/* ITM Integration Mode Control Register Definitions */
-#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */
-#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */
-
-/* ITM Lock Status Register Definitions */
-#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */
-#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
-
-#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */
-#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
-
-#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */
-#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */
-
-/*@}*/ /* end of group CMSIS_ITM */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
- \brief Type definitions for the Data Watchpoint and Trace (DWT)
- @{
- */
-
-/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
- */
-typedef struct
-{
- __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
- __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
- __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
- __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
- __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
- __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
- __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
- __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
- __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
- __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */
- __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
- uint32_t RESERVED0[1];
- __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
- __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */
- __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
- uint32_t RESERVED1[1];
- __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
- __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */
- __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
- uint32_t RESERVED2[1];
- __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
- __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */
- __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
-} DWT_Type;
-
-/* DWT Control Register Definitions */
-#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */
-#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
-
-#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */
-#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
-
-#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */
-#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
-
-#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */
-#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
-
-#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */
-#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
-
-#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */
-#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
-
-#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */
-#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
-
-#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */
-#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
-
-#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */
-#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
-
-#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */
-#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
-
-#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */
-#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
-
-#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */
-#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
-
-#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */
-#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
-
-#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */
-#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
-
-#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */
-#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
-
-#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */
-#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
-
-#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */
-#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
-
-#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */
-#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */
-
-/* DWT CPI Count Register Definitions */
-#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */
-#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */
-
-/* DWT Exception Overhead Count Register Definitions */
-#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */
-#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */
-
-/* DWT Sleep Count Register Definitions */
-#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */
-#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
-
-/* DWT LSU Count Register Definitions */
-#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */
-#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */
-
-/* DWT Folded-instruction Count Register Definitions */
-#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */
-#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */
-
-/* DWT Comparator Mask Register Definitions */
-#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */
-#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */
-
-/* DWT Comparator Function Register Definitions */
-#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */
-#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
-
-#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */
-#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */
-
-#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */
-#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */
-
-#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */
-#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
-
-#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */
-#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */
-
-#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */
-#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */
-
-#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */
-#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */
-
-#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */
-#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */
-
-#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */
-#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */
-
-/*@}*/ /* end of group CMSIS_DWT */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_TPI Trace Port Interface (TPI)
- \brief Type definitions for the Trace Port Interface (TPI)
- @{
- */
-
-/** \brief Structure type to access the Trace Port Interface Register (TPI).
- */
-typedef struct
-{
- __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
- __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
- uint32_t RESERVED0[2];
- __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
- uint32_t RESERVED1[55];
- __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
- uint32_t RESERVED2[131];
- __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
- __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
- __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
- uint32_t RESERVED3[759];
- __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
- __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
- __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
- uint32_t RESERVED4[1];
- __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
- __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
- __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
- uint32_t RESERVED5[39];
- __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
- __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
- uint32_t RESERVED7[8];
- __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
- __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
-} TPI_Type;
-
-/* TPI Asynchronous Clock Prescaler Register Definitions */
-#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */
-#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */
-
-/* TPI Selected Pin Protocol Register Definitions */
-#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */
-#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */
-
-/* TPI Formatter and Flush Status Register Definitions */
-#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */
-#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
-
-#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */
-#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
-
-#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */
-#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
-
-#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */
-#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */
-
-/* TPI Formatter and Flush Control Register Definitions */
-#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */
-#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
-
-#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */
-#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
-
-/* TPI TRIGGER Register Definitions */
-#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */
-#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */
-
-/* TPI Integration ETM Data Register Definitions (FIFO0) */
-#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */
-#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
-
-#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */
-#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
-
-#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */
-#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
-
-#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */
-#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
-
-#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */
-#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
-
-#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */
-#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
-
-#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */
-#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */
-
-/* TPI ITATBCTR2 Register Definitions */
-#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */
-#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */
-
-/* TPI Integration ITM Data Register Definitions (FIFO1) */
-#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */
-#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
-
-#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */
-#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
-
-#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */
-#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
-
-#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */
-#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
-
-#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */
-#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
-
-#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */
-#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
-
-#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */
-#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */
-
-/* TPI ITATBCTR0 Register Definitions */
-#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */
-#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */
-
-/* TPI Integration Mode Control Register Definitions */
-#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */
-#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */
-
-/* TPI DEVID Register Definitions */
-#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */
-#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
-
-#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */
-#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
-
-#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */
-#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
-
-#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */
-#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
-
-#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */
-#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
-
-#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */
-#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */
-
-/* TPI DEVTYPE Register Definitions */
-#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */
-#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */
-
-#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */
-#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
-
-/*@}*/ /* end of group CMSIS_TPI */
-
-
-#if (__MPU_PRESENT == 1)
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_MPU Memory Protection Unit (MPU)
- \brief Type definitions for the Memory Protection Unit (MPU)
- @{
- */
-
-/** \brief Structure type to access the Memory Protection Unit (MPU).
- */
-typedef struct
-{
- __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
- __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
- __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */
- __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
- __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */
- __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */
- __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */
- __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */
- __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */
- __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */
- __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */
-} MPU_Type;
-
-/* MPU Type Register */
-#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */
-#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
-
-#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */
-#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
-
-#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */
-#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */
-
-/* MPU Control Register */
-#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */
-#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
-
-#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */
-#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
-
-#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */
-#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */
-
-/* MPU Region Number Register */
-#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */
-#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */
-
-/* MPU Region Base Address Register */
-#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */
-#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
-
-#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */
-#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
-
-#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */
-#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */
-
-/* MPU Region Attribute and Size Register */
-#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */
-#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */
-
-#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: ATTRS.XN Position */
-#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */
-
-#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: ATTRS.AP Position */
-#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */
-
-#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: ATTRS.TEX Position */
-#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */
-
-#define MPU_RASR_S_Pos 18 /*!< MPU RASR: ATTRS.S Position */
-#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */
-
-#define MPU_RASR_C_Pos 17 /*!< MPU RASR: ATTRS.C Position */
-#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */
-
-#define MPU_RASR_B_Pos 16 /*!< MPU RASR: ATTRS.B Position */
-#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */
-
-#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */
-#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
-
-#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */
-#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
-
-#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */
-#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */
-
-/*@} end of group CMSIS_MPU */
-#endif
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
- \brief Type definitions for the Core Debug Registers
- @{
- */
-
-/** \brief Structure type to access the Core Debug Register (CoreDebug).
- */
-typedef struct
-{
- __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
- __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
- __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
- __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
-} CoreDebug_Type;
-
-/* Debug Halting Control and Status Register */
-#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */
-#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
-
-#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */
-#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
-
-#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
-#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
-
-#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */
-#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
-
-#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */
-#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
-
-#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */
-#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
-
-#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */
-#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
-
-#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
-#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
-
-#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */
-#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
-
-#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */
-#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
-
-#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */
-#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
-
-#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */
-#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
-
-/* Debug Core Register Selector Register */
-#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */
-#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
-
-#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */
-#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */
-
-/* Debug Exception and Monitor Control Register */
-#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */
-#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
-
-#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */
-#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
-
-#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */
-#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
-
-#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */
-#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
-
-#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */
-#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
-
-#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */
-#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
-
-#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */
-#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
-
-#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */
-#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
-
-#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */
-#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
-
-#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */
-#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
-
-#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */
-#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
-
-#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */
-#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
-
-#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */
-#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
-
-/*@} end of group CMSIS_CoreDebug */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_core_base Core Definitions
- \brief Definitions for base addresses, unions, and structures.
- @{
- */
-
-/* Memory mapping of Cortex-M3 Hardware */
-#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
-#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
-#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
-#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
-#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */
-#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
-#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
-#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
-
-#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
-#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
-#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
-#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
-#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
-#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
-#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
-#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
-
-#if (__MPU_PRESENT == 1)
- #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
- #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
-#endif
-
-/*@} */
-
-
-
-/*******************************************************************************
- * Hardware Abstraction Layer
- Core Function Interface contains:
- - Core NVIC Functions
- - Core SysTick Functions
- - Core Debug Functions
- - Core Register Access Functions
- ******************************************************************************/
-/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
-*/
-
-
-
-/* ########################## NVIC functions #################################### */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_Core_NVICFunctions NVIC Functions
- \brief Functions that manage interrupts and exceptions via the NVIC.
- @{
- */
-
-/** \brief Set Priority Grouping
-
- The function sets the priority grouping field using the required unlock sequence.
- The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
- Only values from 0..7 are used.
- In case of a conflict between priority grouping and available
- priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
-
- \param [in] PriorityGroup Priority grouping field.
- */
-__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
-{
- uint32_t reg_value;
- uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */
-
- reg_value = SCB->AIRCR; /* read old register configuration */
- reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
- reg_value = (reg_value |
- ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
- (PriorityGroupTmp << 8)); /* Insert write key and priorty group */
- SCB->AIRCR = reg_value;
-}
-
-
-/** \brief Get Priority Grouping
-
- The function reads the priority grouping field from the NVIC Interrupt Controller.
-
- \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
- */
-__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void)
-{
- return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */
-}
-
-
-/** \brief Enable External Interrupt
-
- The function enables a device-specific interrupt in the NVIC interrupt controller.
-
- \param [in] IRQn External interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
-{
- NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */
-}
-
-
-/** \brief Disable External Interrupt
-
- The function disables a device-specific interrupt in the NVIC interrupt controller.
-
- \param [in] IRQn External interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
-{
- NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */
-}
-
-
-/** \brief Get Pending Interrupt
-
- The function reads the pending register in the NVIC and returns the pending bit
- for the specified interrupt.
-
- \param [in] IRQn Interrupt number.
-
- \return 0 Interrupt status is not pending.
- \return 1 Interrupt status is pending.
- */
-__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)
-{
- return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */
-}
-
-
-/** \brief Set Pending Interrupt
-
- The function sets the pending bit of an external interrupt.
-
- \param [in] IRQn Interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)
-{
- NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */
-}
-
-
-/** \brief Clear Pending Interrupt
-
- The function clears the pending bit of an external interrupt.
-
- \param [in] IRQn External interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
-{
- NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */
-}
-
-
-/** \brief Get Active Interrupt
-
- The function reads the active register in NVIC and returns the active bit.
-
- \param [in] IRQn Interrupt number.
-
- \return 0 Interrupt status is not active.
- \return 1 Interrupt status is active.
- */
-__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)
-{
- return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */
-}
-
-
-/** \brief Set Interrupt Priority
-
- The function sets the priority of an interrupt.
-
- \note The priority cannot be set for every core interrupt.
-
- \param [in] IRQn Interrupt number.
- \param [in] priority Priority to set.
- */
-__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
-{
- if(IRQn < 0) {
- SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */
- else {
- NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */
-}
-
-
-/** \brief Get Interrupt Priority
-
- The function reads the priority of an interrupt. The interrupt
- number can be positive to specify an external (device specific)
- interrupt, or negative to specify an internal (core) interrupt.
-
-
- \param [in] IRQn Interrupt number.
- \return Interrupt Priority. Value is aligned automatically to the implemented
- priority bits of the microcontroller.
- */
-__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)
-{
-
- if(IRQn < 0) {
- return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */
- else {
- return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */
-}
-
-
-/** \brief Encode Priority
-
- The function encodes the priority for an interrupt with the given priority group,
- preemptive priority value, and subpriority value.
- In case of a conflict between priority grouping and available
- priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set.
-
- \param [in] PriorityGroup Used priority group.
- \param [in] PreemptPriority Preemptive priority value (starting from 0).
- \param [in] SubPriority Subpriority value (starting from 0).
- \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority().
- */
-__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
-{
- uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
- uint32_t PreemptPriorityBits;
- uint32_t SubPriorityBits;
-
- PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
- SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
-
- return (
- ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |
- ((SubPriority & ((1 << (SubPriorityBits )) - 1)))
- );
-}
-
-
-/** \brief Decode Priority
-
- The function decodes an interrupt priority value with a given priority group to
- preemptive priority value and subpriority value.
- In case of a conflict between priority grouping and available
- priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.
-
- \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority().
- \param [in] PriorityGroup Used priority group.
- \param [out] pPreemptPriority Preemptive priority value (starting from 0).
- \param [out] pSubPriority Subpriority value (starting from 0).
- */
-__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)
-{
- uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
- uint32_t PreemptPriorityBits;
- uint32_t SubPriorityBits;
-
- PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
- SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
-
- *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);
- *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1);
-}
-
-
-/** \brief System Reset
-
- The function initiates a system reset request to reset the MCU.
- */
-__STATIC_INLINE void NVIC_SystemReset(void)
-{
- __DSB(); /* Ensure all outstanding memory accesses included
- buffered write are completed before reset */
- SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) |
- (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
- SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */
- __DSB(); /* Ensure completion of memory access */
- while(1); /* wait until reset */
-}
-
-/*@} end of CMSIS_Core_NVICFunctions */
-
-
-
-/* ################################## SysTick function ############################################ */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_Core_SysTickFunctions SysTick Functions
- \brief Functions that configure the System.
- @{
- */
-
-#if (__Vendor_SysTickConfig == 0)
-
-/** \brief System Tick Configuration
-
- The function initializes the System Timer and its interrupt, and starts the System Tick Timer.
- Counter is in free running mode to generate periodic interrupts.
-
- \param [in] ticks Number of ticks between two interrupts.
-
- \return 0 Function succeeded.
- \return 1 Function failed.
-
- \note When the variable <b>__Vendor_SysTickConfig</b> is set to 1, then the
- function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
- must contain a vendor-specific implementation of this function.
-
- */
-__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
-{
- if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
-
- SysTick->LOAD = ticks - 1; /* set reload register */
- NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */
- SysTick->VAL = 0; /* Load the SysTick Counter Value */
- SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
- SysTick_CTRL_TICKINT_Msk |
- SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
- return (0); /* Function successful */
-}
-
-#endif
-
-/*@} end of CMSIS_Core_SysTickFunctions */
-
-
-
-/* ##################################### Debug In/Output function ########################################### */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_core_DebugFunctions ITM Functions
- \brief Functions that access the ITM debug interface.
- @{
- */
-
-extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
-#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
-
-
-/** \brief ITM Send Character
-
- The function transmits a character via the ITM channel 0, and
- \li Just returns when no debugger is connected that has booked the output.
- \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
-
- \param [in] ch Character to transmit.
-
- \returns Character to transmit.
- */
-__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch)
-{
- if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */
- (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */
- {
- while (ITM->PORT[0].u32 == 0);
- ITM->PORT[0].u8 = (uint8_t) ch;
- }
- return (ch);
-}
-
-
-/** \brief ITM Receive Character
-
- The function inputs a character via the external variable \ref ITM_RxBuffer.
-
- \return Received character.
- \return -1 No character pending.
- */
-__STATIC_INLINE int32_t ITM_ReceiveChar (void) {
- int32_t ch = -1; /* no character available */
-
- if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) {
- ch = ITM_RxBuffer;
- ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
- }
-
- return (ch);
-}
-
-
-/** \brief ITM Check Character
-
- The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
-
- \return 0 No character available.
- \return 1 Character available.
- */
-__STATIC_INLINE int32_t ITM_CheckChar (void) {
-
- if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) {
- return (0); /* no character available */
- } else {
- return (1); /* character available */
- }
-}
-
-/*@} end of CMSIS_core_DebugFunctions */
-
-#endif /* __CORE_CM3_H_DEPENDANT */
-
-#endif /* __CMSIS_GENERIC */
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/src/modules/mathlib/CMSIS/Include/core_cm4.h b/src/modules/mathlib/CMSIS/Include/core_cm4.h
deleted file mode 100644
index 93efd3a7a..000000000
--- a/src/modules/mathlib/CMSIS/Include/core_cm4.h
+++ /dev/null
@@ -1,1772 +0,0 @@
-/**************************************************************************//**
- * @file core_cm4.h
- * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File
- * @version V3.20
- * @date 25. February 2013
- *
- * @note
- *
- ******************************************************************************/
-/* Copyright (c) 2009 - 2013 ARM LIMITED
-
- All rights reserved.
- Redistribution and use in source and binary forms, with or without
- modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - 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.
- - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- ---------------------------------------------------------------------------*/
-
-
-#if defined ( __ICCARM__ )
- #pragma system_include /* treat file as system include file for MISRA check */
-#endif
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-#ifndef __CORE_CM4_H_GENERIC
-#define __CORE_CM4_H_GENERIC
-
-/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
- CMSIS violates the following MISRA-C:2004 rules:
-
- \li Required Rule 8.5, object/function definition in header file.<br>
- Function definitions in header files are used to allow 'inlining'.
-
- \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
- Unions are used for effective representation of core registers.
-
- \li Advisory Rule 19.7, Function-like macro defined.<br>
- Function-like macros are used to allow more efficient code.
- */
-
-
-/*******************************************************************************
- * CMSIS definitions
- ******************************************************************************/
-/** \ingroup Cortex_M4
- @{
- */
-
-/* CMSIS CM4 definitions */
-#define __CM4_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */
-#define __CM4_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
-#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | \
- __CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */
-
-#define __CORTEX_M (0x04) /*!< Cortex-M Core */
-
-
-#if defined ( __CC_ARM )
- #define __ASM __asm /*!< asm keyword for ARM Compiler */
- #define __INLINE __inline /*!< inline keyword for ARM Compiler */
- #define __STATIC_INLINE static __inline
-
-#elif defined ( __ICCARM__ )
- #define __ASM __asm /*!< asm keyword for IAR Compiler */
- #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */
- #define __STATIC_INLINE static inline
-
-#elif defined ( __TMS470__ )
- #define __ASM __asm /*!< asm keyword for TI CCS Compiler */
- #define __STATIC_INLINE static inline
-
-#elif defined ( __GNUC__ )
- #define __ASM __asm /*!< asm keyword for GNU Compiler */
- #define __INLINE inline /*!< inline keyword for GNU Compiler */
- #define __STATIC_INLINE static inline
-
-#elif defined ( __TASKING__ )
- #define __ASM __asm /*!< asm keyword for TASKING Compiler */
- #define __INLINE inline /*!< inline keyword for TASKING Compiler */
- #define __STATIC_INLINE static inline
-
-#endif
-
-/** __FPU_USED indicates whether an FPU is used or not. For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions.
-*/
-#if defined ( __CC_ARM )
- #if defined __TARGET_FPU_VFP
- #if (__FPU_PRESENT == 1)
- #define __FPU_USED 1
- #else
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #define __FPU_USED 0
- #endif
- #else
- #define __FPU_USED 0
- #endif
-
-#elif defined ( __ICCARM__ )
- #if defined __ARMVFP__
- #if (__FPU_PRESENT == 1)
- #define __FPU_USED 1
- #else
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #define __FPU_USED 0
- #endif
- #else
- #define __FPU_USED 0
- #endif
-
-#elif defined ( __TMS470__ )
- #if defined __TI_VFP_SUPPORT__
- #if (__FPU_PRESENT == 1)
- #define __FPU_USED 1
- #else
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #define __FPU_USED 0
- #endif
- #else
- #define __FPU_USED 0
- #endif
-
-#elif defined ( __GNUC__ )
- #if defined (__VFP_FP__) && !defined(__SOFTFP__)
- #if (__FPU_PRESENT == 1)
- #define __FPU_USED 1
- #else
- #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #define __FPU_USED 0
- #endif
- #else
- #define __FPU_USED 0
- #endif
-
-#elif defined ( __TASKING__ )
- #if defined __FPU_VFP__
- #if (__FPU_PRESENT == 1)
- #define __FPU_USED 1
- #else
- #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
- #define __FPU_USED 0
- #endif
- #else
- #define __FPU_USED 0
- #endif
-#endif
-
-#include <stdint.h> /* standard types definitions */
-#include "core_cmInstr.h" /* Core Instruction Access */
-#include "core_cmFunc.h" /* Core Function Access */
-#include "core_cm4_simd.h" /* Compiler specific SIMD Intrinsics */
-
-#endif /* __CORE_CM4_H_GENERIC */
-
-#ifndef __CMSIS_GENERIC
-
-#ifndef __CORE_CM4_H_DEPENDANT
-#define __CORE_CM4_H_DEPENDANT
-
-/* check device defines and use defaults */
-#if defined __CHECK_DEVICE_DEFINES
- #ifndef __CM4_REV
- #define __CM4_REV 0x0000
- #warning "__CM4_REV not defined in device header file; using default!"
- #endif
-
- #ifndef __FPU_PRESENT
- #define __FPU_PRESENT 0
- #warning "__FPU_PRESENT not defined in device header file; using default!"
- #endif
-
- #ifndef __MPU_PRESENT
- #define __MPU_PRESENT 0
- #warning "__MPU_PRESENT not defined in device header file; using default!"
- #endif
-
- #ifndef __NVIC_PRIO_BITS
- #define __NVIC_PRIO_BITS 4
- #warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
- #endif
-
- #ifndef __Vendor_SysTickConfig
- #define __Vendor_SysTickConfig 0
- #warning "__Vendor_SysTickConfig not defined in device header file; using default!"
- #endif
-#endif
-
-/* IO definitions (access restrictions to peripheral registers) */
-/**
- \defgroup CMSIS_glob_defs CMSIS Global Defines
-
- <strong>IO Type Qualifiers</strong> are used
- \li to specify the access to peripheral variables.
- \li for automatic generation of peripheral register debug information.
-*/
-#ifdef __cplusplus
- #define __I volatile /*!< Defines 'read only' permissions */
-#else
- #define __I volatile const /*!< Defines 'read only' permissions */
-#endif
-#define __O volatile /*!< Defines 'write only' permissions */
-#define __IO volatile /*!< Defines 'read / write' permissions */
-
-/*@} end of group Cortex_M4 */
-
-
-
-/*******************************************************************************
- * Register Abstraction
- Core Register contain:
- - Core Register
- - Core NVIC Register
- - Core SCB Register
- - Core SysTick Register
- - Core Debug Register
- - Core MPU Register
- - Core FPU Register
- ******************************************************************************/
-/** \defgroup CMSIS_core_register Defines and Type Definitions
- \brief Type definitions and defines for Cortex-M processor based devices.
-*/
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_CORE Status and Control Registers
- \brief Core Register type definitions.
- @{
- */
-
-/** \brief Union type to access the Application Program Status Register (APSR).
- */
-typedef union
-{
- struct
- {
-#if (__CORTEX_M != 0x04)
- uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */
-#else
- uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */
- uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
- uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */
-#endif
- uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
- uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
- uint32_t C:1; /*!< bit: 29 Carry condition code flag */
- uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
- uint32_t N:1; /*!< bit: 31 Negative condition code flag */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} APSR_Type;
-
-
-/** \brief Union type to access the Interrupt Program Status Register (IPSR).
- */
-typedef union
-{
- struct
- {
- uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
- uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} IPSR_Type;
-
-
-/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR).
- */
-typedef union
-{
- struct
- {
- uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
-#if (__CORTEX_M != 0x04)
- uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */
-#else
- uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */
- uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
- uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */
-#endif
- uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
- uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */
- uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
- uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
- uint32_t C:1; /*!< bit: 29 Carry condition code flag */
- uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
- uint32_t N:1; /*!< bit: 31 Negative condition code flag */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} xPSR_Type;
-
-
-/** \brief Union type to access the Control Registers (CONTROL).
- */
-typedef union
-{
- struct
- {
- uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
- uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
- uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */
- uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */
- } b; /*!< Structure used for bit access */
- uint32_t w; /*!< Type used for word access */
-} CONTROL_Type;
-
-/*@} end of group CMSIS_CORE */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
- \brief Type definitions for the NVIC Registers
- @{
- */
-
-/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
- */
-typedef struct
-{
- __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
- uint32_t RESERVED0[24];
- __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
- uint32_t RSERVED1[24];
- __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
- uint32_t RESERVED2[24];
- __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
- uint32_t RESERVED3[24];
- __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
- uint32_t RESERVED4[56];
- __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
- uint32_t RESERVED5[644];
- __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
-} NVIC_Type;
-
-/* Software Triggered Interrupt Register Definitions */
-#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */
-#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */
-
-/*@} end of group CMSIS_NVIC */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_SCB System Control Block (SCB)
- \brief Type definitions for the System Control Block Registers
- @{
- */
-
-/** \brief Structure type to access the System Control Block (SCB).
- */
-typedef struct
-{
- __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
- __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
- __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
- __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
- __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
- __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
- __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
- __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
- __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
- __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
- __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
- __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
- __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
- __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
- __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
- __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
- __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
- __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
- __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
- uint32_t RESERVED0[5];
- __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
-} SCB_Type;
-
-/* SCB CPUID Register Definitions */
-#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */
-#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
-
-#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */
-#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
-
-#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */
-#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
-
-#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */
-#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
-
-#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */
-#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */
-
-/* SCB Interrupt Control State Register Definitions */
-#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */
-#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
-
-#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */
-#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
-
-#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */
-#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
-
-#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */
-#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
-
-#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */
-#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
-
-#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */
-#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
-
-#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */
-#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
-
-#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */
-#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
-
-#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */
-#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */
-
-#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */
-#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */
-
-/* SCB Vector Table Offset Register Definitions */
-#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
-#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
-
-/* SCB Application Interrupt and Reset Control Register Definitions */
-#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
-#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
-
-#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */
-#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
-
-#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */
-#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
-
-#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
-#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
-
-#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */
-#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
-
-#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */
-#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
-
-#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */
-#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */
-
-/* SCB System Control Register Definitions */
-#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */
-#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
-
-#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */
-#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
-
-#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */
-#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
-
-/* SCB Configuration Control Register Definitions */
-#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */
-#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
-
-#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */
-#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
-
-#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */
-#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */
-
-#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */
-#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
-
-#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */
-#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
-
-#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */
-#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */
-
-/* SCB System Handler Control and State Register Definitions */
-#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */
-#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
-
-#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */
-#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
-
-#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */
-#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
-
-#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */
-#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
-
-#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */
-#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
-
-#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */
-#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
-
-#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */
-#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
-
-#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */
-#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
-
-#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */
-#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
-
-#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */
-#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
-
-#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */
-#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
-
-#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */
-#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
-
-#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */
-#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
-
-#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */
-#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */
-
-/* SCB Configurable Fault Status Registers Definitions */
-#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */
-#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
-
-#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */
-#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
-
-#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */
-#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
-
-/* SCB Hard Fault Status Registers Definitions */
-#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */
-#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
-
-#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */
-#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
-
-#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */
-#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
-
-/* SCB Debug Fault Status Register Definitions */
-#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */
-#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
-
-#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */
-#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
-
-#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */
-#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
-
-#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */
-#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
-
-#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */
-#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */
-
-/*@} end of group CMSIS_SCB */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
- \brief Type definitions for the System Control and ID Register not in the SCB
- @{
- */
-
-/** \brief Structure type to access the System Control and ID Register not in the SCB.
- */
-typedef struct
-{
- uint32_t RESERVED0[1];
- __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
- __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
-} SCnSCB_Type;
-
-/* Interrupt Controller Type Register Definitions */
-#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */
-#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */
-
-/* Auxiliary Control Register Definitions */
-#define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */
-#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */
-
-#define SCnSCB_ACTLR_DISFPCA_Pos 8 /*!< ACTLR: DISFPCA Position */
-#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */
-
-#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */
-#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */
-
-#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */
-#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */
-
-#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */
-#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */
-
-/*@} end of group CMSIS_SCnotSCB */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_SysTick System Tick Timer (SysTick)
- \brief Type definitions for the System Timer Registers.
- @{
- */
-
-/** \brief Structure type to access the System Timer (SysTick).
- */
-typedef struct
-{
- __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
- __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
- __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
- __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
-} SysTick_Type;
-
-/* SysTick Control / Status Register Definitions */
-#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */
-#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
-
-#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */
-#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
-
-#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */
-#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
-
-#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */
-#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */
-
-/* SysTick Reload Register Definitions */
-#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */
-#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */
-
-/* SysTick Current Register Definitions */
-#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */
-#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */
-
-/* SysTick Calibration Register Definitions */
-#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */
-#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
-
-#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */
-#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
-
-#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */
-#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */
-
-/*@} end of group CMSIS_SysTick */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM)
- \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
- @{
- */
-
-/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
- */
-typedef struct
-{
- __O union
- {
- __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
- __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
- __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
- } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
- uint32_t RESERVED0[864];
- __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
- uint32_t RESERVED1[15];
- __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
- uint32_t RESERVED2[15];
- __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
- uint32_t RESERVED3[29];
- __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
- __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
- __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
- uint32_t RESERVED4[43];
- __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
- __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
- uint32_t RESERVED5[6];
- __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
- __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
- __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
- __I uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
- __I uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
- __I uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
- __I uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
- __I uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
- __I uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
- __I uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
- __I uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
- __I uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
-} ITM_Type;
-
-/* ITM Trace Privilege Register Definitions */
-#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */
-#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */
-
-/* ITM Trace Control Register Definitions */
-#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */
-#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
-
-#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */
-#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */
-
-#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */
-#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
-
-#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */
-#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
-
-#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */
-#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
-
-#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */
-#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
-
-#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */
-#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
-
-#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */
-#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
-
-#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */
-#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */
-
-/* ITM Integration Write Register Definitions */
-#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */
-#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */
-
-/* ITM Integration Read Register Definitions */
-#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */
-#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */
-
-/* ITM Integration Mode Control Register Definitions */
-#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */
-#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */
-
-/* ITM Lock Status Register Definitions */
-#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */
-#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
-
-#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */
-#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
-
-#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */
-#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */
-
-/*@}*/ /* end of group CMSIS_ITM */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
- \brief Type definitions for the Data Watchpoint and Trace (DWT)
- @{
- */
-
-/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
- */
-typedef struct
-{
- __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
- __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
- __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
- __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
- __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
- __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
- __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
- __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
- __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
- __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */
- __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
- uint32_t RESERVED0[1];
- __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
- __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */
- __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
- uint32_t RESERVED1[1];
- __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
- __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */
- __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
- uint32_t RESERVED2[1];
- __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
- __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */
- __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
-} DWT_Type;
-
-/* DWT Control Register Definitions */
-#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */
-#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
-
-#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */
-#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
-
-#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */
-#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
-
-#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */
-#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
-
-#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */
-#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
-
-#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */
-#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
-
-#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */
-#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
-
-#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */
-#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
-
-#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */
-#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
-
-#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */
-#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
-
-#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */
-#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
-
-#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */
-#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
-
-#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */
-#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
-
-#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */
-#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
-
-#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */
-#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
-
-#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */
-#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
-
-#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */
-#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
-
-#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */
-#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */
-
-/* DWT CPI Count Register Definitions */
-#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */
-#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */
-
-/* DWT Exception Overhead Count Register Definitions */
-#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */
-#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */
-
-/* DWT Sleep Count Register Definitions */
-#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */
-#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
-
-/* DWT LSU Count Register Definitions */
-#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */
-#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */
-
-/* DWT Folded-instruction Count Register Definitions */
-#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */
-#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */
-
-/* DWT Comparator Mask Register Definitions */
-#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */
-#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */
-
-/* DWT Comparator Function Register Definitions */
-#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */
-#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
-
-#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */
-#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */
-
-#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */
-#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */
-
-#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */
-#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
-
-#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */
-#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */
-
-#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */
-#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */
-
-#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */
-#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */
-
-#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */
-#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */
-
-#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */
-#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */
-
-/*@}*/ /* end of group CMSIS_DWT */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_TPI Trace Port Interface (TPI)
- \brief Type definitions for the Trace Port Interface (TPI)
- @{
- */
-
-/** \brief Structure type to access the Trace Port Interface Register (TPI).
- */
-typedef struct
-{
- __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
- __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
- uint32_t RESERVED0[2];
- __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
- uint32_t RESERVED1[55];
- __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
- uint32_t RESERVED2[131];
- __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
- __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
- __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
- uint32_t RESERVED3[759];
- __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
- __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
- __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
- uint32_t RESERVED4[1];
- __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
- __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
- __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
- uint32_t RESERVED5[39];
- __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
- __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
- uint32_t RESERVED7[8];
- __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
- __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
-} TPI_Type;
-
-/* TPI Asynchronous Clock Prescaler Register Definitions */
-#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */
-#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */
-
-/* TPI Selected Pin Protocol Register Definitions */
-#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */
-#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */
-
-/* TPI Formatter and Flush Status Register Definitions */
-#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */
-#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
-
-#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */
-#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
-
-#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */
-#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
-
-#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */
-#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */
-
-/* TPI Formatter and Flush Control Register Definitions */
-#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */
-#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
-
-#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */
-#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
-
-/* TPI TRIGGER Register Definitions */
-#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */
-#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */
-
-/* TPI Integration ETM Data Register Definitions (FIFO0) */
-#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */
-#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
-
-#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */
-#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
-
-#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */
-#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
-
-#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */
-#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
-
-#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */
-#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
-
-#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */
-#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
-
-#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */
-#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */
-
-/* TPI ITATBCTR2 Register Definitions */
-#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */
-#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */
-
-/* TPI Integration ITM Data Register Definitions (FIFO1) */
-#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */
-#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
-
-#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */
-#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
-
-#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */
-#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
-
-#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */
-#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
-
-#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */
-#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
-
-#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */
-#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
-
-#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */
-#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */
-
-/* TPI ITATBCTR0 Register Definitions */
-#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */
-#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */
-
-/* TPI Integration Mode Control Register Definitions */
-#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */
-#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */
-
-/* TPI DEVID Register Definitions */
-#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */
-#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
-
-#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */
-#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
-
-#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */
-#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
-
-#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */
-#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
-
-#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */
-#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
-
-#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */
-#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */
-
-/* TPI DEVTYPE Register Definitions */
-#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */
-#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */
-
-#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */
-#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
-
-/*@}*/ /* end of group CMSIS_TPI */
-
-
-#if (__MPU_PRESENT == 1)
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_MPU Memory Protection Unit (MPU)
- \brief Type definitions for the Memory Protection Unit (MPU)
- @{
- */
-
-/** \brief Structure type to access the Memory Protection Unit (MPU).
- */
-typedef struct
-{
- __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
- __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
- __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */
- __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
- __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */
- __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */
- __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */
- __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */
- __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */
- __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */
- __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */
-} MPU_Type;
-
-/* MPU Type Register */
-#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */
-#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
-
-#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */
-#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
-
-#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */
-#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */
-
-/* MPU Control Register */
-#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */
-#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
-
-#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */
-#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
-
-#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */
-#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */
-
-/* MPU Region Number Register */
-#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */
-#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */
-
-/* MPU Region Base Address Register */
-#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */
-#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
-
-#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */
-#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
-
-#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */
-#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */
-
-/* MPU Region Attribute and Size Register */
-#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */
-#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */
-
-#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: ATTRS.XN Position */
-#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */
-
-#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: ATTRS.AP Position */
-#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */
-
-#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: ATTRS.TEX Position */
-#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */
-
-#define MPU_RASR_S_Pos 18 /*!< MPU RASR: ATTRS.S Position */
-#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */
-
-#define MPU_RASR_C_Pos 17 /*!< MPU RASR: ATTRS.C Position */
-#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */
-
-#define MPU_RASR_B_Pos 16 /*!< MPU RASR: ATTRS.B Position */
-#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */
-
-#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */
-#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
-
-#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */
-#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
-
-#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */
-#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */
-
-/*@} end of group CMSIS_MPU */
-#endif
-
-
-#if (__FPU_PRESENT == 1)
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_FPU Floating Point Unit (FPU)
- \brief Type definitions for the Floating Point Unit (FPU)
- @{
- */
-
-/** \brief Structure type to access the Floating Point Unit (FPU).
- */
-typedef struct
-{
- uint32_t RESERVED0[1];
- __IO uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */
- __IO uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */
- __IO uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */
- __I uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */
- __I uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */
-} FPU_Type;
-
-/* Floating-Point Context Control Register */
-#define FPU_FPCCR_ASPEN_Pos 31 /*!< FPCCR: ASPEN bit Position */
-#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */
-
-#define FPU_FPCCR_LSPEN_Pos 30 /*!< FPCCR: LSPEN Position */
-#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */
-
-#define FPU_FPCCR_MONRDY_Pos 8 /*!< FPCCR: MONRDY Position */
-#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */
-
-#define FPU_FPCCR_BFRDY_Pos 6 /*!< FPCCR: BFRDY Position */
-#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */
-
-#define FPU_FPCCR_MMRDY_Pos 5 /*!< FPCCR: MMRDY Position */
-#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */
-
-#define FPU_FPCCR_HFRDY_Pos 4 /*!< FPCCR: HFRDY Position */
-#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */
-
-#define FPU_FPCCR_THREAD_Pos 3 /*!< FPCCR: processor mode bit Position */
-#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */
-
-#define FPU_FPCCR_USER_Pos 1 /*!< FPCCR: privilege level bit Position */
-#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */
-
-#define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */
-#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */
-
-/* Floating-Point Context Address Register */
-#define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */
-#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */
-
-/* Floating-Point Default Status Control Register */
-#define FPU_FPDSCR_AHP_Pos 26 /*!< FPDSCR: AHP bit Position */
-#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */
-
-#define FPU_FPDSCR_DN_Pos 25 /*!< FPDSCR: DN bit Position */
-#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */
-
-#define FPU_FPDSCR_FZ_Pos 24 /*!< FPDSCR: FZ bit Position */
-#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */
-
-#define FPU_FPDSCR_RMode_Pos 22 /*!< FPDSCR: RMode bit Position */
-#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */
-
-/* Media and FP Feature Register 0 */
-#define FPU_MVFR0_FP_rounding_modes_Pos 28 /*!< MVFR0: FP rounding modes bits Position */
-#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */
-
-#define FPU_MVFR0_Short_vectors_Pos 24 /*!< MVFR0: Short vectors bits Position */
-#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */
-
-#define FPU_MVFR0_Square_root_Pos 20 /*!< MVFR0: Square root bits Position */
-#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */
-
-#define FPU_MVFR0_Divide_Pos 16 /*!< MVFR0: Divide bits Position */
-#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */
-
-#define FPU_MVFR0_FP_excep_trapping_Pos 12 /*!< MVFR0: FP exception trapping bits Position */
-#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */
-
-#define FPU_MVFR0_Double_precision_Pos 8 /*!< MVFR0: Double-precision bits Position */
-#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */
-
-#define FPU_MVFR0_Single_precision_Pos 4 /*!< MVFR0: Single-precision bits Position */
-#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */
-
-#define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< MVFR0: A_SIMD registers bits Position */
-#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL << FPU_MVFR0_A_SIMD_registers_Pos) /*!< MVFR0: A_SIMD registers bits Mask */
-
-/* Media and FP Feature Register 1 */
-#define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */
-#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */
-
-#define FPU_MVFR1_FP_HPFP_Pos 24 /*!< MVFR1: FP HPFP bits Position */
-#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */
-
-#define FPU_MVFR1_D_NaN_mode_Pos 4 /*!< MVFR1: D_NaN mode bits Position */
-#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */
-
-#define FPU_MVFR1_FtZ_mode_Pos 0 /*!< MVFR1: FtZ mode bits Position */
-#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */
-
-/*@} end of group CMSIS_FPU */
-#endif
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
- \brief Type definitions for the Core Debug Registers
- @{
- */
-
-/** \brief Structure type to access the Core Debug Register (CoreDebug).
- */
-typedef struct
-{
- __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
- __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
- __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
- __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
-} CoreDebug_Type;
-
-/* Debug Halting Control and Status Register */
-#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */
-#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
-
-#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */
-#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
-
-#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
-#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
-
-#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */
-#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
-
-#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */
-#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
-
-#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */
-#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
-
-#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */
-#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
-
-#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
-#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
-
-#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */
-#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
-
-#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */
-#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
-
-#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */
-#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
-
-#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */
-#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
-
-/* Debug Core Register Selector Register */
-#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */
-#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
-
-#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */
-#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */
-
-/* Debug Exception and Monitor Control Register */
-#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */
-#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
-
-#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */
-#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
-
-#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */
-#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
-
-#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */
-#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
-
-#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */
-#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
-
-#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */
-#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
-
-#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */
-#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
-
-#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */
-#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
-
-#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */
-#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
-
-#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */
-#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
-
-#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */
-#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
-
-#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */
-#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
-
-#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */
-#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
-
-/*@} end of group CMSIS_CoreDebug */
-
-
-/** \ingroup CMSIS_core_register
- \defgroup CMSIS_core_base Core Definitions
- \brief Definitions for base addresses, unions, and structures.
- @{
- */
-
-/* Memory mapping of Cortex-M4 Hardware */
-#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
-#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
-#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
-#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
-#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */
-#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
-#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
-#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
-
-#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
-#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
-#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
-#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
-#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
-#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
-#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
-#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
-
-#if (__MPU_PRESENT == 1)
- #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
- #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
-#endif
-
-#if (__FPU_PRESENT == 1)
- #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */
- #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */
-#endif
-
-/*@} */
-
-
-
-/*******************************************************************************
- * Hardware Abstraction Layer
- Core Function Interface contains:
- - Core NVIC Functions
- - Core SysTick Functions
- - Core Debug Functions
- - Core Register Access Functions
- ******************************************************************************/
-/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
-*/
-
-
-
-/* ########################## NVIC functions #################################### */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_Core_NVICFunctions NVIC Functions
- \brief Functions that manage interrupts and exceptions via the NVIC.
- @{
- */
-
-/** \brief Set Priority Grouping
-
- The function sets the priority grouping field using the required unlock sequence.
- The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
- Only values from 0..7 are used.
- In case of a conflict between priority grouping and available
- priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
-
- \param [in] PriorityGroup Priority grouping field.
- */
-__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
-{
- uint32_t reg_value;
- uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */
-
- reg_value = SCB->AIRCR; /* read old register configuration */
- reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
- reg_value = (reg_value |
- ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
- (PriorityGroupTmp << 8)); /* Insert write key and priorty group */
- SCB->AIRCR = reg_value;
-}
-
-
-/** \brief Get Priority Grouping
-
- The function reads the priority grouping field from the NVIC Interrupt Controller.
-
- \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
- */
-__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void)
-{
- return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */
-}
-
-
-/** \brief Enable External Interrupt
-
- The function enables a device-specific interrupt in the NVIC interrupt controller.
-
- \param [in] IRQn External interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
-{
-/* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */
- NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */
-}
-
-
-/** \brief Disable External Interrupt
-
- The function disables a device-specific interrupt in the NVIC interrupt controller.
-
- \param [in] IRQn External interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
-{
- NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */
-}
-
-
-/** \brief Get Pending Interrupt
-
- The function reads the pending register in the NVIC and returns the pending bit
- for the specified interrupt.
-
- \param [in] IRQn Interrupt number.
-
- \return 0 Interrupt status is not pending.
- \return 1 Interrupt status is pending.
- */
-__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)
-{
- return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */
-}
-
-
-/** \brief Set Pending Interrupt
-
- The function sets the pending bit of an external interrupt.
-
- \param [in] IRQn Interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)
-{
- NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */
-}
-
-
-/** \brief Clear Pending Interrupt
-
- The function clears the pending bit of an external interrupt.
-
- \param [in] IRQn External interrupt number. Value cannot be negative.
- */
-__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
-{
- NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */
-}
-
-
-/** \brief Get Active Interrupt
-
- The function reads the active register in NVIC and returns the active bit.
-
- \param [in] IRQn Interrupt number.
-
- \return 0 Interrupt status is not active.
- \return 1 Interrupt status is active.
- */
-__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)
-{
- return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */
-}
-
-
-/** \brief Set Interrupt Priority
-
- The function sets the priority of an interrupt.
-
- \note The priority cannot be set for every core interrupt.
-
- \param [in] IRQn Interrupt number.
- \param [in] priority Priority to set.
- */
-__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
-{
- if(IRQn < 0) {
- SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */
- else {
- NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */
-}
-
-
-/** \brief Get Interrupt Priority
-
- The function reads the priority of an interrupt. The interrupt
- number can be positive to specify an external (device specific)
- interrupt, or negative to specify an internal (core) interrupt.
-
-
- \param [in] IRQn Interrupt number.
- \return Interrupt Priority. Value is aligned automatically to the implemented
- priority bits of the microcontroller.
- */
-__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)
-{
-
- if(IRQn < 0) {
- return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */
- else {
- return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */
-}
-
-
-/** \brief Encode Priority
-
- The function encodes the priority for an interrupt with the given priority group,
- preemptive priority value, and subpriority value.
- In case of a conflict between priority grouping and available
- priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set.
-
- \param [in] PriorityGroup Used priority group.
- \param [in] PreemptPriority Preemptive priority value (starting from 0).
- \param [in] SubPriority Subpriority value (starting from 0).
- \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority().
- */
-__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
-{
- uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
- uint32_t PreemptPriorityBits;
- uint32_t SubPriorityBits;
-
- PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
- SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
-
- return (
- ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |
- ((SubPriority & ((1 << (SubPriorityBits )) - 1)))
- );
-}
-
-
-/** \brief Decode Priority
-
- The function decodes an interrupt priority value with a given priority group to
- preemptive priority value and subpriority value.
- In case of a conflict between priority grouping and available
- priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.
-
- \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority().
- \param [in] PriorityGroup Used priority group.
- \param [out] pPreemptPriority Preemptive priority value (starting from 0).
- \param [out] pSubPriority Subpriority value (starting from 0).
- */
-__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)
-{
- uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
- uint32_t PreemptPriorityBits;
- uint32_t SubPriorityBits;
-
- PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
- SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
-
- *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);
- *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1);
-}
-
-
-/** \brief System Reset
-
- The function initiates a system reset request to reset the MCU.
- */
-__STATIC_INLINE void NVIC_SystemReset(void)
-{
- __DSB(); /* Ensure all outstanding memory accesses included
- buffered write are completed before reset */
- SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) |
- (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
- SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */
- __DSB(); /* Ensure completion of memory access */
- while(1); /* wait until reset */
-}
-
-/*@} end of CMSIS_Core_NVICFunctions */
-
-
-
-/* ################################## SysTick function ############################################ */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_Core_SysTickFunctions SysTick Functions
- \brief Functions that configure the System.
- @{
- */
-
-#if (__Vendor_SysTickConfig == 0)
-
-/** \brief System Tick Configuration
-
- The function initializes the System Timer and its interrupt, and starts the System Tick Timer.
- Counter is in free running mode to generate periodic interrupts.
-
- \param [in] ticks Number of ticks between two interrupts.
-
- \return 0 Function succeeded.
- \return 1 Function failed.
-
- \note When the variable <b>__Vendor_SysTickConfig</b> is set to 1, then the
- function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
- must contain a vendor-specific implementation of this function.
-
- */
-__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
-{
- if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
-
- SysTick->LOAD = ticks - 1; /* set reload register */
- NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */
- SysTick->VAL = 0; /* Load the SysTick Counter Value */
- SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
- SysTick_CTRL_TICKINT_Msk |
- SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
- return (0); /* Function successful */
-}
-
-#endif
-
-/*@} end of CMSIS_Core_SysTickFunctions */
-
-
-
-/* ##################################### Debug In/Output function ########################################### */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_core_DebugFunctions ITM Functions
- \brief Functions that access the ITM debug interface.
- @{
- */
-
-extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
-#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
-
-
-/** \brief ITM Send Character
-
- The function transmits a character via the ITM channel 0, and
- \li Just returns when no debugger is connected that has booked the output.
- \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
-
- \param [in] ch Character to transmit.
-
- \returns Character to transmit.
- */
-__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch)
-{
- if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */
- (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */
- {
- while (ITM->PORT[0].u32 == 0);
- ITM->PORT[0].u8 = (uint8_t) ch;
- }
- return (ch);
-}
-
-
-/** \brief ITM Receive Character
-
- The function inputs a character via the external variable \ref ITM_RxBuffer.
-
- \return Received character.
- \return -1 No character pending.
- */
-__STATIC_INLINE int32_t ITM_ReceiveChar (void) {
- int32_t ch = -1; /* no character available */
-
- if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) {
- ch = ITM_RxBuffer;
- ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
- }
-
- return (ch);
-}
-
-
-/** \brief ITM Check Character
-
- The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
-
- \return 0 No character available.
- \return 1 Character available.
- */
-__STATIC_INLINE int32_t ITM_CheckChar (void) {
-
- if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) {
- return (0); /* no character available */
- } else {
- return (1); /* character available */
- }
-}
-
-/*@} end of CMSIS_core_DebugFunctions */
-
-#endif /* __CORE_CM4_H_DEPENDANT */
-
-#endif /* __CMSIS_GENERIC */
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h b/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h
deleted file mode 100644
index af1831ee1..000000000
--- a/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h
+++ /dev/null
@@ -1,673 +0,0 @@
-/**************************************************************************//**
- * @file core_cm4_simd.h
- * @brief CMSIS Cortex-M4 SIMD Header File
- * @version V3.20
- * @date 25. February 2013
- *
- * @note
- *
- ******************************************************************************/
-/* Copyright (c) 2009 - 2013 ARM LIMITED
-
- All rights reserved.
- Redistribution and use in source and binary forms, with or without
- modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - 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.
- - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- ---------------------------------------------------------------------------*/
-
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-#ifndef __CORE_CM4_SIMD_H
-#define __CORE_CM4_SIMD_H
-
-
-/*******************************************************************************
- * Hardware Abstraction Layer
- ******************************************************************************/
-
-
-/* ################### Compiler specific Intrinsics ########################### */
-/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
- Access to dedicated SIMD instructions
- @{
-*/
-
-#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
-/* ARM armcc specific functions */
-
-/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
-#define __SADD8 __sadd8
-#define __QADD8 __qadd8
-#define __SHADD8 __shadd8
-#define __UADD8 __uadd8
-#define __UQADD8 __uqadd8
-#define __UHADD8 __uhadd8
-#define __SSUB8 __ssub8
-#define __QSUB8 __qsub8
-#define __SHSUB8 __shsub8
-#define __USUB8 __usub8
-#define __UQSUB8 __uqsub8
-#define __UHSUB8 __uhsub8
-#define __SADD16 __sadd16
-#define __QADD16 __qadd16
-#define __SHADD16 __shadd16
-#define __UADD16 __uadd16
-#define __UQADD16 __uqadd16
-#define __UHADD16 __uhadd16
-#define __SSUB16 __ssub16
-#define __QSUB16 __qsub16
-#define __SHSUB16 __shsub16
-#define __USUB16 __usub16
-#define __UQSUB16 __uqsub16
-#define __UHSUB16 __uhsub16
-#define __SASX __sasx
-#define __QASX __qasx
-#define __SHASX __shasx
-#define __UASX __uasx
-#define __UQASX __uqasx
-#define __UHASX __uhasx
-#define __SSAX __ssax
-#define __QSAX __qsax
-#define __SHSAX __shsax
-#define __USAX __usax
-#define __UQSAX __uqsax
-#define __UHSAX __uhsax
-#define __USAD8 __usad8
-#define __USADA8 __usada8
-#define __SSAT16 __ssat16
-#define __USAT16 __usat16
-#define __UXTB16 __uxtb16
-#define __UXTAB16 __uxtab16
-#define __SXTB16 __sxtb16
-#define __SXTAB16 __sxtab16
-#define __SMUAD __smuad
-#define __SMUADX __smuadx
-#define __SMLAD __smlad
-#define __SMLADX __smladx
-#define __SMLALD __smlald
-#define __SMLALDX __smlaldx
-#define __SMUSD __smusd
-#define __SMUSDX __smusdx
-#define __SMLSD __smlsd
-#define __SMLSDX __smlsdx
-#define __SMLSLD __smlsld
-#define __SMLSLDX __smlsldx
-#define __SEL __sel
-#define __QADD __qadd
-#define __QSUB __qsub
-
-#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \
- ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) )
-
-#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \
- ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) )
-
-#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \
- ((int64_t)(ARG3) << 32) ) >> 32))
-
-/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
-
-
-
-#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
-/* IAR iccarm specific functions */
-
-/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
-#include <cmsis_iar.h>
-
-/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
-
-
-
-#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
-/* TI CCS specific functions */
-
-/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
-#include <cmsis_ccs.h>
-
-/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
-
-
-
-#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
-/* GNU gcc specific functions */
-
-/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3)
-{
- uint32_t result;
-
- __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
- return(result);
-}
-
-#define __SSAT16(ARG1,ARG2) \
-({ \
- uint32_t __RES, __ARG1 = (ARG1); \
- __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
- __RES; \
- })
-
-#define __USAT16(ARG1,ARG2) \
-({ \
- uint32_t __RES, __ARG1 = (ARG1); \
- __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
- __RES; \
- })
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1)
-{
- uint32_t result;
-
- __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1));
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1)
-{
- uint32_t result;
-
- __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1));
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3)
-{
- uint32_t result;
-
- __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3)
-{
- uint32_t result;
-
- __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
- return(result);
-}
-
-#define __SMLALD(ARG1,ARG2,ARG3) \
-({ \
- uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \
- __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
- (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
- })
-
-#define __SMLALDX(ARG1,ARG2,ARG3) \
-({ \
- uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \
- __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
- (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
- })
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3)
-{
- uint32_t result;
-
- __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3)
-{
- uint32_t result;
-
- __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
- return(result);
-}
-
-#define __SMLSLD(ARG1,ARG2,ARG3) \
-({ \
- uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \
- __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
- (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
- })
-
-#define __SMLSLDX(ARG1,ARG2,ARG3) \
-({ \
- uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \
- __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
- (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
- })
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2)
-{
- uint32_t result;
-
- __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
- return(result);
-}
-
-#define __PKHBT(ARG1,ARG2,ARG3) \
-({ \
- uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
- __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
- __RES; \
- })
-
-#define __PKHTB(ARG1,ARG2,ARG3) \
-({ \
- uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
- if (ARG3 == 0) \
- __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \
- else \
- __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
- __RES; \
- })
-
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3)
-{
- int32_t result;
-
- __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) );
- return(result);
-}
-
-/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
-
-
-
-#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
-/* TASKING carm specific functions */
-
-
-/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
-/* not yet supported */
-/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
-
-
-#endif
-
-/*@} end of group CMSIS_SIMD_intrinsics */
-
-
-#endif /* __CORE_CM4_SIMD_H */
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/src/modules/mathlib/CMSIS/Include/core_cmFunc.h b/src/modules/mathlib/CMSIS/Include/core_cmFunc.h
deleted file mode 100644
index 139bc3c5e..000000000
--- a/src/modules/mathlib/CMSIS/Include/core_cmFunc.h
+++ /dev/null
@@ -1,636 +0,0 @@
-/**************************************************************************//**
- * @file core_cmFunc.h
- * @brief CMSIS Cortex-M Core Function Access Header File
- * @version V3.20
- * @date 25. February 2013
- *
- * @note
- *
- ******************************************************************************/
-/* Copyright (c) 2009 - 2013 ARM LIMITED
-
- All rights reserved.
- Redistribution and use in source and binary forms, with or without
- modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - 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.
- - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- ---------------------------------------------------------------------------*/
-
-
-#ifndef __CORE_CMFUNC_H
-#define __CORE_CMFUNC_H
-
-
-/* ########################### Core Function Access ########################### */
-/** \ingroup CMSIS_Core_FunctionInterface
- \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
- @{
- */
-
-#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
-/* ARM armcc specific functions */
-
-#if (__ARMCC_VERSION < 400677)
- #error "Please use ARM Compiler Toolchain V4.0.677 or later!"
-#endif
-
-/* intrinsic void __enable_irq(); */
-/* intrinsic void __disable_irq(); */
-
-/** \brief Get Control Register
-
- This function returns the content of the Control Register.
-
- \return Control Register value
- */
-__STATIC_INLINE uint32_t __get_CONTROL(void)
-{
- register uint32_t __regControl __ASM("control");
- return(__regControl);
-}
-
-
-/** \brief Set Control Register
-
- This function writes the given value to the Control Register.
-
- \param [in] control Control Register value to set
- */
-__STATIC_INLINE void __set_CONTROL(uint32_t control)
-{
- register uint32_t __regControl __ASM("control");
- __regControl = control;
-}
-
-
-/** \brief Get IPSR Register
-
- This function returns the content of the IPSR Register.
-
- \return IPSR Register value
- */
-__STATIC_INLINE uint32_t __get_IPSR(void)
-{
- register uint32_t __regIPSR __ASM("ipsr");
- return(__regIPSR);
-}
-
-
-/** \brief Get APSR Register
-
- This function returns the content of the APSR Register.
-
- \return APSR Register value
- */
-__STATIC_INLINE uint32_t __get_APSR(void)
-{
- register uint32_t __regAPSR __ASM("apsr");
- return(__regAPSR);
-}
-
-
-/** \brief Get xPSR Register
-
- This function returns the content of the xPSR Register.
-
- \return xPSR Register value
- */
-__STATIC_INLINE uint32_t __get_xPSR(void)
-{
- register uint32_t __regXPSR __ASM("xpsr");
- return(__regXPSR);
-}
-
-
-/** \brief Get Process Stack Pointer
-
- This function returns the current value of the Process Stack Pointer (PSP).
-
- \return PSP Register value
- */
-__STATIC_INLINE uint32_t __get_PSP(void)
-{
- register uint32_t __regProcessStackPointer __ASM("psp");
- return(__regProcessStackPointer);
-}
-
-
-/** \brief Set Process Stack Pointer
-
- This function assigns the given value to the Process Stack Pointer (PSP).
-
- \param [in] topOfProcStack Process Stack Pointer value to set
- */
-__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
-{
- register uint32_t __regProcessStackPointer __ASM("psp");
- __regProcessStackPointer = topOfProcStack;
-}
-
-
-/** \brief Get Main Stack Pointer
-
- This function returns the current value of the Main Stack Pointer (MSP).
-
- \return MSP Register value
- */
-__STATIC_INLINE uint32_t __get_MSP(void)
-{
- register uint32_t __regMainStackPointer __ASM("msp");
- return(__regMainStackPointer);
-}
-
-
-/** \brief Set Main Stack Pointer
-
- This function assigns the given value to the Main Stack Pointer (MSP).
-
- \param [in] topOfMainStack Main Stack Pointer value to set
- */
-__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
-{
- register uint32_t __regMainStackPointer __ASM("msp");
- __regMainStackPointer = topOfMainStack;
-}
-
-
-/** \brief Get Priority Mask
-
- This function returns the current state of the priority mask bit from the Priority Mask Register.
-
- \return Priority Mask value
- */
-__STATIC_INLINE uint32_t __get_PRIMASK(void)
-{
- register uint32_t __regPriMask __ASM("primask");
- return(__regPriMask);
-}
-
-
-/** \brief Set Priority Mask
-
- This function assigns the given value to the Priority Mask Register.
-
- \param [in] priMask Priority Mask
- */
-__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
-{
- register uint32_t __regPriMask __ASM("primask");
- __regPriMask = (priMask);
-}
-
-
-#if (__CORTEX_M >= 0x03)
-
-/** \brief Enable FIQ
-
- This function enables FIQ interrupts by clearing the F-bit in the CPSR.
- Can only be executed in Privileged modes.
- */
-#define __enable_fault_irq __enable_fiq
-
-
-/** \brief Disable FIQ
-
- This function disables FIQ interrupts by setting the F-bit in the CPSR.
- Can only be executed in Privileged modes.
- */
-#define __disable_fault_irq __disable_fiq
-
-
-/** \brief Get Base Priority
-
- This function returns the current value of the Base Priority register.
-
- \return Base Priority register value
- */
-__STATIC_INLINE uint32_t __get_BASEPRI(void)
-{
- register uint32_t __regBasePri __ASM("basepri");
- return(__regBasePri);
-}
-
-
-/** \brief Set Base Priority
-
- This function assigns the given value to the Base Priority register.
-
- \param [in] basePri Base Priority value to set
- */
-__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
-{
- register uint32_t __regBasePri __ASM("basepri");
- __regBasePri = (basePri & 0xff);
-}
-
-
-/** \brief Get Fault Mask
-
- This function returns the current value of the Fault Mask register.
-
- \return Fault Mask register value
- */
-__STATIC_INLINE uint32_t __get_FAULTMASK(void)
-{
- register uint32_t __regFaultMask __ASM("faultmask");
- return(__regFaultMask);
-}
-
-
-/** \brief Set Fault Mask
-
- This function assigns the given value to the Fault Mask register.
-
- \param [in] faultMask Fault Mask value to set
- */
-__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
-{
- register uint32_t __regFaultMask __ASM("faultmask");
- __regFaultMask = (faultMask & (uint32_t)1);
-}
-
-#endif /* (__CORTEX_M >= 0x03) */
-
-
-#if (__CORTEX_M == 0x04)
-
-/** \brief Get FPSCR
-
- This function returns the current value of the Floating Point Status/Control register.
-
- \return Floating Point Status/Control register value
- */
-__STATIC_INLINE uint32_t __get_FPSCR(void)
-{
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
- register uint32_t __regfpscr __ASM("fpscr");
- return(__regfpscr);
-#else
- return(0);
-#endif
-}
-
-
-/** \brief Set FPSCR
-
- This function assigns the given value to the Floating Point Status/Control register.
-
- \param [in] fpscr Floating Point Status/Control value to set
- */
-__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
-{
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
- register uint32_t __regfpscr __ASM("fpscr");
- __regfpscr = (fpscr);
-#endif
-}
-
-#endif /* (__CORTEX_M == 0x04) */
-
-
-#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
-/* IAR iccarm specific functions */
-
-#include <cmsis_iar.h>
-
-
-#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
-/* TI CCS specific functions */
-
-#include <cmsis_ccs.h>
-
-
-#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
-/* GNU gcc specific functions */
-
-/** \brief Enable IRQ Interrupts
-
- This function enables IRQ interrupts by clearing the I-bit in the CPSR.
- Can only be executed in Privileged modes.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void)
-{
- __ASM volatile ("cpsie i" : : : "memory");
-}
-
-
-/** \brief Disable IRQ Interrupts
-
- This function disables IRQ interrupts by setting the I-bit in the CPSR.
- Can only be executed in Privileged modes.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void)
-{
- __ASM volatile ("cpsid i" : : : "memory");
-}
-
-
-/** \brief Get Control Register
-
- This function returns the content of the Control Register.
-
- \return Control Register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, control" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Set Control Register
-
- This function writes the given value to the Control Register.
-
- \param [in] control Control Register value to set
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control)
-{
- __ASM volatile ("MSR control, %0" : : "r" (control) : "memory");
-}
-
-
-/** \brief Get IPSR Register
-
- This function returns the content of the IPSR Register.
-
- \return IPSR Register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, ipsr" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Get APSR Register
-
- This function returns the content of the APSR Register.
-
- \return APSR Register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, apsr" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Get xPSR Register
-
- This function returns the content of the xPSR Register.
-
- \return xPSR Register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, xpsr" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Get Process Stack Pointer
-
- This function returns the current value of the Process Stack Pointer (PSP).
-
- \return PSP Register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void)
-{
- register uint32_t result;
-
- __ASM volatile ("MRS %0, psp\n" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Set Process Stack Pointer
-
- This function assigns the given value to the Process Stack Pointer (PSP).
-
- \param [in] topOfProcStack Process Stack Pointer value to set
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
-{
- __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp");
-}
-
-
-/** \brief Get Main Stack Pointer
-
- This function returns the current value of the Main Stack Pointer (MSP).
-
- \return MSP Register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void)
-{
- register uint32_t result;
-
- __ASM volatile ("MRS %0, msp\n" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Set Main Stack Pointer
-
- This function assigns the given value to the Main Stack Pointer (MSP).
-
- \param [in] topOfMainStack Main Stack Pointer value to set
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
-{
- __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp");
-}
-
-
-/** \brief Get Priority Mask
-
- This function returns the current state of the priority mask bit from the Priority Mask Register.
-
- \return Priority Mask value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, primask" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Set Priority Mask
-
- This function assigns the given value to the Priority Mask Register.
-
- \param [in] priMask Priority Mask
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
-{
- __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory");
-}
-
-
-#if (__CORTEX_M >= 0x03)
-
-/** \brief Enable FIQ
-
- This function enables FIQ interrupts by clearing the F-bit in the CPSR.
- Can only be executed in Privileged modes.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void)
-{
- __ASM volatile ("cpsie f" : : : "memory");
-}
-
-
-/** \brief Disable FIQ
-
- This function disables FIQ interrupts by setting the F-bit in the CPSR.
- Can only be executed in Privileged modes.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void)
-{
- __ASM volatile ("cpsid f" : : : "memory");
-}
-
-
-/** \brief Get Base Priority
-
- This function returns the current value of the Base Priority register.
-
- \return Base Priority register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Set Base Priority
-
- This function assigns the given value to the Base Priority register.
-
- \param [in] basePri Base Priority value to set
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value)
-{
- __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory");
-}
-
-
-/** \brief Get Fault Mask
-
- This function returns the current value of the Fault Mask register.
-
- \return Fault Mask register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void)
-{
- uint32_t result;
-
- __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
- return(result);
-}
-
-
-/** \brief Set Fault Mask
-
- This function assigns the given value to the Fault Mask register.
-
- \param [in] faultMask Fault Mask value to set
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
-{
- __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory");
-}
-
-#endif /* (__CORTEX_M >= 0x03) */
-
-
-#if (__CORTEX_M == 0x04)
-
-/** \brief Get FPSCR
-
- This function returns the current value of the Floating Point Status/Control register.
-
- \return Floating Point Status/Control register value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void)
-{
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
- uint32_t result;
-
- /* Empty asm statement works as a scheduling barrier */
- __ASM volatile ("");
- __ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
- __ASM volatile ("");
- return(result);
-#else
- return(0);
-#endif
-}
-
-
-/** \brief Set FPSCR
-
- This function assigns the given value to the Floating Point Status/Control register.
-
- \param [in] fpscr Floating Point Status/Control value to set
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
-{
-#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
- /* Empty asm statement works as a scheduling barrier */
- __ASM volatile ("");
- __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc");
- __ASM volatile ("");
-#endif
-}
-
-#endif /* (__CORTEX_M == 0x04) */
-
-
-#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
-/* TASKING carm specific functions */
-
-/*
- * The CMSIS functions have been implemented as intrinsics in the compiler.
- * Please use "carm -?i" to get an up to date list of all instrinsics,
- * Including the CMSIS ones.
- */
-
-#endif
-
-/*@} end of CMSIS_Core_RegAccFunctions */
-
-
-#endif /* __CORE_CMFUNC_H */
diff --git a/src/modules/mathlib/CMSIS/Include/core_cmInstr.h b/src/modules/mathlib/CMSIS/Include/core_cmInstr.h
deleted file mode 100644
index 8946c2c49..000000000
--- a/src/modules/mathlib/CMSIS/Include/core_cmInstr.h
+++ /dev/null
@@ -1,688 +0,0 @@
-/**************************************************************************//**
- * @file core_cmInstr.h
- * @brief CMSIS Cortex-M Core Instruction Access Header File
- * @version V3.20
- * @date 05. March 2013
- *
- * @note
- *
- ******************************************************************************/
-/* Copyright (c) 2009 - 2013 ARM LIMITED
-
- All rights reserved.
- Redistribution and use in source and binary forms, with or without
- modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - 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.
- - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- ---------------------------------------------------------------------------*/
-
-
-#ifndef __CORE_CMINSTR_H
-#define __CORE_CMINSTR_H
-
-
-/* ########################## Core Instruction Access ######################### */
-/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
- Access to dedicated instructions
- @{
-*/
-
-#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
-/* ARM armcc specific functions */
-
-#if (__ARMCC_VERSION < 400677)
- #error "Please use ARM Compiler Toolchain V4.0.677 or later!"
-#endif
-
-
-/** \brief No Operation
-
- No Operation does nothing. This instruction can be used for code alignment purposes.
- */
-#define __NOP __nop
-
-
-/** \brief Wait For Interrupt
-
- Wait For Interrupt is a hint instruction that suspends execution
- until one of a number of events occurs.
- */
-#define __WFI __wfi
-
-
-/** \brief Wait For Event
-
- Wait For Event is a hint instruction that permits the processor to enter
- a low-power state until one of a number of events occurs.
- */
-#define __WFE __wfe
-
-
-/** \brief Send Event
-
- Send Event is a hint instruction. It causes an event to be signaled to the CPU.
- */
-#define __SEV __sev
-
-
-/** \brief Instruction Synchronization Barrier
-
- Instruction Synchronization Barrier flushes the pipeline in the processor,
- so that all instructions following the ISB are fetched from cache or
- memory, after the instruction has been completed.
- */
-#define __ISB() __isb(0xF)
-
-
-/** \brief Data Synchronization Barrier
-
- This function acts as a special kind of Data Memory Barrier.
- It completes when all explicit memory accesses before this instruction complete.
- */
-#define __DSB() __dsb(0xF)
-
-
-/** \brief Data Memory Barrier
-
- This function ensures the apparent order of the explicit memory operations before
- and after the instruction, without ensuring their completion.
- */
-#define __DMB() __dmb(0xF)
-
-
-/** \brief Reverse byte order (32 bit)
-
- This function reverses the byte order in integer value.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-#define __REV __rev
-
-
-/** \brief Reverse byte order (16 bit)
-
- This function reverses the byte order in two unsigned short values.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-#ifndef __NO_EMBEDDED_ASM
-__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
-{
- rev16 r0, r0
- bx lr
-}
-#endif
-
-/** \brief Reverse byte order in signed short value
-
- This function reverses the byte order in a signed short value with sign extension to integer.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-#ifndef __NO_EMBEDDED_ASM
-__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value)
-{
- revsh r0, r0
- bx lr
-}
-#endif
-
-
-/** \brief Rotate Right in unsigned value (32 bit)
-
- This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
-
- \param [in] value Value to rotate
- \param [in] value Number of Bits to rotate
- \return Rotated value
- */
-#define __ROR __ror
-
-
-/** \brief Breakpoint
-
- This function causes the processor to enter Debug state.
- Debug tools can use this to investigate system state when the instruction at a particular address is reached.
-
- \param [in] value is ignored by the processor.
- If required, a debugger can use it to store additional information about the breakpoint.
- */
-#define __BKPT(value) __breakpoint(value)
-
-
-#if (__CORTEX_M >= 0x03)
-
-/** \brief Reverse bit order of value
-
- This function reverses the bit order of the given value.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-#define __RBIT __rbit
-
-
-/** \brief LDR Exclusive (8 bit)
-
- This function performs a exclusive LDR command for 8 bit value.
-
- \param [in] ptr Pointer to data
- \return value of type uint8_t at (*ptr)
- */
-#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
-
-
-/** \brief LDR Exclusive (16 bit)
-
- This function performs a exclusive LDR command for 16 bit values.
-
- \param [in] ptr Pointer to data
- \return value of type uint16_t at (*ptr)
- */
-#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
-
-
-/** \brief LDR Exclusive (32 bit)
-
- This function performs a exclusive LDR command for 32 bit values.
-
- \param [in] ptr Pointer to data
- \return value of type uint32_t at (*ptr)
- */
-#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
-
-
-/** \brief STR Exclusive (8 bit)
-
- This function performs a exclusive STR command for 8 bit values.
-
- \param [in] value Value to store
- \param [in] ptr Pointer to location
- \return 0 Function succeeded
- \return 1 Function failed
- */
-#define __STREXB(value, ptr) __strex(value, ptr)
-
-
-/** \brief STR Exclusive (16 bit)
-
- This function performs a exclusive STR command for 16 bit values.
-
- \param [in] value Value to store
- \param [in] ptr Pointer to location
- \return 0 Function succeeded
- \return 1 Function failed
- */
-#define __STREXH(value, ptr) __strex(value, ptr)
-
-
-/** \brief STR Exclusive (32 bit)
-
- This function performs a exclusive STR command for 32 bit values.
-
- \param [in] value Value to store
- \param [in] ptr Pointer to location
- \return 0 Function succeeded
- \return 1 Function failed
- */
-#define __STREXW(value, ptr) __strex(value, ptr)
-
-
-/** \brief Remove the exclusive lock
-
- This function removes the exclusive lock which is created by LDREX.
-
- */
-#define __CLREX __clrex
-
-
-/** \brief Signed Saturate
-
- This function saturates a signed value.
-
- \param [in] value Value to be saturated
- \param [in] sat Bit position to saturate to (1..32)
- \return Saturated value
- */
-#define __SSAT __ssat
-
-
-/** \brief Unsigned Saturate
-
- This function saturates an unsigned value.
-
- \param [in] value Value to be saturated
- \param [in] sat Bit position to saturate to (0..31)
- \return Saturated value
- */
-#define __USAT __usat
-
-
-/** \brief Count leading zeros
-
- This function counts the number of leading zeros of a data value.
-
- \param [in] value Value to count the leading zeros
- \return number of leading zeros in value
- */
-#define __CLZ __clz
-
-#endif /* (__CORTEX_M >= 0x03) */
-
-
-
-#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
-/* IAR iccarm specific functions */
-
-#include <cmsis_iar.h>
-
-
-#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
-/* TI CCS specific functions */
-
-#include <cmsis_ccs.h>
-
-
-#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
-/* GNU gcc specific functions */
-
-/* Define macros for porting to both thumb1 and thumb2.
- * For thumb1, use low register (r0-r7), specified by constrant "l"
- * Otherwise, use general registers, specified by constrant "r" */
-#if defined (__thumb__) && !defined (__thumb2__)
-#define __CMSIS_GCC_OUT_REG(r) "=l" (r)
-#define __CMSIS_GCC_USE_REG(r) "l" (r)
-#else
-#define __CMSIS_GCC_OUT_REG(r) "=r" (r)
-#define __CMSIS_GCC_USE_REG(r) "r" (r)
-#endif
-
-/** \brief No Operation
-
- No Operation does nothing. This instruction can be used for code alignment purposes.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void)
-{
- __ASM volatile ("nop");
-}
-
-
-/** \brief Wait For Interrupt
-
- Wait For Interrupt is a hint instruction that suspends execution
- until one of a number of events occurs.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void)
-{
- __ASM volatile ("wfi");
-}
-
-
-/** \brief Wait For Event
-
- Wait For Event is a hint instruction that permits the processor to enter
- a low-power state until one of a number of events occurs.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void)
-{
- __ASM volatile ("wfe");
-}
-
-
-/** \brief Send Event
-
- Send Event is a hint instruction. It causes an event to be signaled to the CPU.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void)
-{
- __ASM volatile ("sev");
-}
-
-
-/** \brief Instruction Synchronization Barrier
-
- Instruction Synchronization Barrier flushes the pipeline in the processor,
- so that all instructions following the ISB are fetched from cache or
- memory, after the instruction has been completed.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void)
-{
- __ASM volatile ("isb");
-}
-
-
-/** \brief Data Synchronization Barrier
-
- This function acts as a special kind of Data Memory Barrier.
- It completes when all explicit memory accesses before this instruction complete.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void)
-{
- __ASM volatile ("dsb");
-}
-
-
-/** \brief Data Memory Barrier
-
- This function ensures the apparent order of the explicit memory operations before
- and after the instruction, without ensuring their completion.
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void)
-{
- __ASM volatile ("dmb");
-}
-
-
-/** \brief Reverse byte order (32 bit)
-
- This function reverses the byte order in integer value.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value)
-{
-#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5)
- return __builtin_bswap32(value);
-#else
- uint32_t result;
-
- __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
- return(result);
-#endif
-}
-
-
-/** \brief Reverse byte order (16 bit)
-
- This function reverses the byte order in two unsigned short values.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value)
-{
- uint32_t result;
-
- __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
- return(result);
-}
-
-
-/** \brief Reverse byte order in signed short value
-
- This function reverses the byte order in a signed short value with sign extension to integer.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value)
-{
-#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
- return (short)__builtin_bswap16(value);
-#else
- uint32_t result;
-
- __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
- return(result);
-#endif
-}
-
-
-/** \brief Rotate Right in unsigned value (32 bit)
-
- This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
-
- \param [in] value Value to rotate
- \param [in] value Number of Bits to rotate
- \return Rotated value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
-{
- return (op1 >> op2) | (op1 << (32 - op2));
-}
-
-
-/** \brief Breakpoint
-
- This function causes the processor to enter Debug state.
- Debug tools can use this to investigate system state when the instruction at a particular address is reached.
-
- \param [in] value is ignored by the processor.
- If required, a debugger can use it to store additional information about the breakpoint.
- */
-#define __BKPT(value) __ASM volatile ("bkpt "#value)
-
-
-#if (__CORTEX_M >= 0x03)
-
-/** \brief Reverse bit order of value
-
- This function reverses the bit order of the given value.
-
- \param [in] value Value to reverse
- \return Reversed value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
-{
- uint32_t result;
-
- __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
- return(result);
-}
-
-
-/** \brief LDR Exclusive (8 bit)
-
- This function performs a exclusive LDR command for 8 bit value.
-
- \param [in] ptr Pointer to data
- \return value of type uint8_t at (*ptr)
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr)
-{
- uint32_t result;
-
-#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
- __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) );
-#else
- /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
- accepted by assembler. So has to use following less efficient pattern.
- */
- __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" );
-#endif
- return(result);
-}
-
-
-/** \brief LDR Exclusive (16 bit)
-
- This function performs a exclusive LDR command for 16 bit values.
-
- \param [in] ptr Pointer to data
- \return value of type uint16_t at (*ptr)
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr)
-{
- uint32_t result;
-
-#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
- __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) );
-#else
- /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
- accepted by assembler. So has to use following less efficient pattern.
- */
- __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" );
-#endif
- return(result);
-}
-
-
-/** \brief LDR Exclusive (32 bit)
-
- This function performs a exclusive LDR command for 32 bit values.
-
- \param [in] ptr Pointer to data
- \return value of type uint32_t at (*ptr)
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr)
-{
- uint32_t result;
-
- __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) );
- return(result);
-}
-
-
-/** \brief STR Exclusive (8 bit)
-
- This function performs a exclusive STR command for 8 bit values.
-
- \param [in] value Value to store
- \param [in] ptr Pointer to location
- \return 0 Function succeeded
- \return 1 Function failed
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
-{
- uint32_t result;
-
- __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
- return(result);
-}
-
-
-/** \brief STR Exclusive (16 bit)
-
- This function performs a exclusive STR command for 16 bit values.
-
- \param [in] value Value to store
- \param [in] ptr Pointer to location
- \return 0 Function succeeded
- \return 1 Function failed
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
-{
- uint32_t result;
-
- __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
- return(result);
-}
-
-
-/** \brief STR Exclusive (32 bit)
-
- This function performs a exclusive STR command for 32 bit values.
-
- \param [in] value Value to store
- \param [in] ptr Pointer to location
- \return 0 Function succeeded
- \return 1 Function failed
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
-{
- uint32_t result;
-
- __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
- return(result);
-}
-
-
-/** \brief Remove the exclusive lock
-
- This function removes the exclusive lock which is created by LDREX.
-
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void)
-{
- __ASM volatile ("clrex" ::: "memory");
-}
-
-
-/** \brief Signed Saturate
-
- This function saturates a signed value.
-
- \param [in] value Value to be saturated
- \param [in] sat Bit position to saturate to (1..32)
- \return Saturated value
- */
-#define __SSAT(ARG1,ARG2) \
-({ \
- uint32_t __RES, __ARG1 = (ARG1); \
- __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
- __RES; \
- })
-
-
-/** \brief Unsigned Saturate
-
- This function saturates an unsigned value.
-
- \param [in] value Value to be saturated
- \param [in] sat Bit position to saturate to (0..31)
- \return Saturated value
- */
-#define __USAT(ARG1,ARG2) \
-({ \
- uint32_t __RES, __ARG1 = (ARG1); \
- __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
- __RES; \
- })
-
-
-/** \brief Count leading zeros
-
- This function counts the number of leading zeros of a data value.
-
- \param [in] value Value to count the leading zeros
- \return number of leading zeros in value
- */
-__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value)
-{
- uint32_t result;
-
- __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) );
- return(result);
-}
-
-#endif /* (__CORTEX_M >= 0x03) */
-
-
-
-
-#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
-/* TASKING carm specific functions */
-
-/*
- * The CMSIS functions have been implemented as intrinsics in the compiler.
- * Please use "carm -?i" to get an up to date list of all intrinsics,
- * Including the CMSIS ones.
- */
-
-#endif
-
-/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
-
-#endif /* __CORE_CMINSTR_H */
diff --git a/src/modules/mathlib/CMSIS/libarm_cortexM3l_math.a b/src/modules/mathlib/CMSIS/libarm_cortexM3l_math.a
deleted file mode 100644
index 6898bc27d..000000000
--- a/src/modules/mathlib/CMSIS/libarm_cortexM3l_math.a
+++ /dev/null
Binary files differ
diff --git a/src/modules/mathlib/CMSIS/libarm_cortexM4l_math.a b/src/modules/mathlib/CMSIS/libarm_cortexM4l_math.a
deleted file mode 100755
index a0185eaa9..000000000
--- a/src/modules/mathlib/CMSIS/libarm_cortexM4l_math.a
+++ /dev/null
Binary files differ
diff --git a/src/modules/mathlib/CMSIS/libarm_cortexM4lf_math.a b/src/modules/mathlib/CMSIS/libarm_cortexM4lf_math.a
deleted file mode 100755
index 94525528e..000000000
--- a/src/modules/mathlib/CMSIS/libarm_cortexM4lf_math.a
+++ /dev/null
Binary files differ
diff --git a/src/modules/mathlib/CMSIS/license.txt b/src/modules/mathlib/CMSIS/license.txt
deleted file mode 100644
index 31afac1ec..000000000
--- a/src/modules/mathlib/CMSIS/license.txt
+++ /dev/null
@@ -1,27 +0,0 @@
-All pre-built libraries are guided by the following license:
-
-Copyright (C) 2009-2012 ARM Limited.
-All rights reserved.
-
-Redistribution and use in source and binary forms, with or without
-modification, are permitted provided that the following conditions are met:
- - Redistributions of source code must retain the above copyright
- notice, this list of conditions and the following disclaimer.
- - 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.
- - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
diff --git a/src/modules/mathlib/math/Dcm.cpp b/src/modules/mathlib/math/Dcm.cpp
deleted file mode 100644
index c3742e288..000000000
--- a/src/modules/mathlib/math/Dcm.cpp
+++ /dev/null
@@ -1,165 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Dcm.cpp
- *
- * math direction cosine matrix
- */
-
-#include <mathlib/math/test/test.hpp>
-
-#include "Dcm.hpp"
-#include "Quaternion.hpp"
-#include "EulerAngles.hpp"
-#include "Vector3.hpp"
-
-namespace math
-{
-
-Dcm::Dcm() :
- Matrix(Matrix::identity(3))
-{
-}
-
-Dcm::Dcm(float c00, float c01, float c02,
- float c10, float c11, float c12,
- float c20, float c21, float c22) :
- Matrix(3, 3)
-{
- Dcm &dcm = *this;
- dcm(0, 0) = c00;
- dcm(0, 1) = c01;
- dcm(0, 2) = c02;
- dcm(1, 0) = c10;
- dcm(1, 1) = c11;
- dcm(1, 2) = c12;
- dcm(2, 0) = c20;
- dcm(2, 1) = c21;
- dcm(2, 2) = c22;
-}
-
-Dcm::Dcm(const float *data) :
- Matrix(3, 3, data)
-{
-}
-
-Dcm::Dcm(const Quaternion &q) :
- Matrix(3, 3)
-{
- Dcm &dcm = *this;
- double a = q.getA();
- double b = q.getB();
- double c = q.getC();
- double d = q.getD();
- double aSq = a * a;
- double bSq = b * b;
- double cSq = c * c;
- double dSq = d * d;
- dcm(0, 0) = aSq + bSq - cSq - dSq;
- dcm(0, 1) = 2.0 * (b * c - a * d);
- dcm(0, 2) = 2.0 * (a * c + b * d);
- dcm(1, 0) = 2.0 * (b * c + a * d);
- dcm(1, 1) = aSq - bSq + cSq - dSq;
- dcm(1, 2) = 2.0 * (c * d - a * b);
- dcm(2, 0) = 2.0 * (b * d - a * c);
- dcm(2, 1) = 2.0 * (a * b + c * d);
- dcm(2, 2) = aSq - bSq - cSq + dSq;
-}
-
-Dcm::Dcm(const EulerAngles &euler) :
- Matrix(3, 3)
-{
- Dcm &dcm = *this;
- double cosPhi = cos(euler.getPhi());
- double sinPhi = sin(euler.getPhi());
- double cosThe = cos(euler.getTheta());
- double sinThe = sin(euler.getTheta());
- double cosPsi = cos(euler.getPsi());
- double sinPsi = sin(euler.getPsi());
-
- dcm(0, 0) = cosThe * cosPsi;
- dcm(0, 1) = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
- dcm(0, 2) = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
-
- dcm(1, 0) = cosThe * sinPsi;
- dcm(1, 1) = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
- dcm(1, 2) = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
-
- dcm(2, 0) = -sinThe;
- dcm(2, 1) = sinPhi * cosThe;
- dcm(2, 2) = cosPhi * cosThe;
-}
-
-Dcm::Dcm(const Dcm &right) :
- Matrix(right)
-{
-}
-
-Dcm::~Dcm()
-{
-}
-
-int __EXPORT dcmTest()
-{
- printf("Test DCM\t\t: ");
- // default ctor
- ASSERT(matrixEqual(Dcm(),
- Matrix::identity(3)));
- // quaternion ctor
- ASSERT(matrixEqual(
- Dcm(Quaternion(0.983347f, 0.034271f, 0.106021f, 0.143572f)),
- Dcm(0.9362934f, -0.2750958f, 0.2183507f,
- 0.2896295f, 0.9564251f, -0.0369570f,
- -0.1986693f, 0.0978434f, 0.9751703f)));
- // euler angle ctor
- ASSERT(matrixEqual(
- Dcm(EulerAngles(0.1f, 0.2f, 0.3f)),
- Dcm(0.9362934f, -0.2750958f, 0.2183507f,
- 0.2896295f, 0.9564251f, -0.0369570f,
- -0.1986693f, 0.0978434f, 0.9751703f)));
- // rotations
- Vector3 vB(1, 2, 3);
- ASSERT(vectorEqual(Vector3(-2.0f, 1.0f, 3.0f),
- Dcm(EulerAngles(0.0f, 0.0f, M_PI_2_F))*vB));
- ASSERT(vectorEqual(Vector3(3.0f, 2.0f, -1.0f),
- Dcm(EulerAngles(0.0f, M_PI_2_F, 0.0f))*vB));
- ASSERT(vectorEqual(Vector3(1.0f, -3.0f, 2.0f),
- Dcm(EulerAngles(M_PI_2_F, 0.0f, 0.0f))*vB));
- ASSERT(vectorEqual(Vector3(3.0f, 2.0f, -1.0f),
- Dcm(EulerAngles(
- M_PI_2_F, M_PI_2_F, M_PI_2_F))*vB));
- printf("PASS\n");
- return 0;
-}
-} // namespace math
diff --git a/src/modules/mathlib/math/EulerAngles.cpp b/src/modules/mathlib/math/EulerAngles.cpp
deleted file mode 100644
index e733d23bb..000000000
--- a/src/modules/mathlib/math/EulerAngles.cpp
+++ /dev/null
@@ -1,126 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Vector.cpp
- *
- * math vector
- */
-
-#include "test/test.hpp"
-
-#include "EulerAngles.hpp"
-#include "Quaternion.hpp"
-#include "Dcm.hpp"
-#include "Vector3.hpp"
-
-namespace math
-{
-
-EulerAngles::EulerAngles() :
- Vector(3)
-{
- setPhi(0.0f);
- setTheta(0.0f);
- setPsi(0.0f);
-}
-
-EulerAngles::EulerAngles(float phi, float theta, float psi) :
- Vector(3)
-{
- setPhi(phi);
- setTheta(theta);
- setPsi(psi);
-}
-
-EulerAngles::EulerAngles(const Quaternion &q) :
- Vector(3)
-{
- (*this) = EulerAngles(Dcm(q));
-}
-
-EulerAngles::EulerAngles(const Dcm &dcm) :
- Vector(3)
-{
- setTheta(asinf(-dcm(2, 0)));
-
- if (fabsf(getTheta() - M_PI_2_F) < 1.0e-3f) {
- setPhi(0.0f);
- setPsi(atan2f(dcm(1, 2) - dcm(0, 1),
- dcm(0, 2) + dcm(1, 1)) + getPhi());
-
- } else if (fabsf(getTheta() + M_PI_2_F) < 1.0e-3f) {
- setPhi(0.0f);
- setPsi(atan2f(dcm(1, 2) - dcm(0, 1),
- dcm(0, 2) + dcm(1, 1)) - getPhi());
-
- } else {
- setPhi(atan2f(dcm(2, 1), dcm(2, 2)));
- setPsi(atan2f(dcm(1, 0), dcm(0, 0)));
- }
-}
-
-EulerAngles::~EulerAngles()
-{
-}
-
-int __EXPORT eulerAnglesTest()
-{
- printf("Test EulerAngles\t: ");
- EulerAngles euler(0.1f, 0.2f, 0.3f);
-
- // test ctor
- ASSERT(vectorEqual(Vector3(0.1f, 0.2f, 0.3f), euler));
- ASSERT(equal(euler.getPhi(), 0.1f));
- ASSERT(equal(euler.getTheta(), 0.2f));
- ASSERT(equal(euler.getPsi(), 0.3f));
-
- // test dcm ctor
- euler = Dcm(EulerAngles(0.1f, 0.2f, 0.3f));
- ASSERT(vectorEqual(Vector3(0.1f, 0.2f, 0.3f), euler));
-
- // test quat ctor
- euler = Quaternion(EulerAngles(0.1f, 0.2f, 0.3f));
- ASSERT(vectorEqual(Vector3(0.1f, 0.2f, 0.3f), euler));
-
- // test assignment
- euler.setPhi(0.4f);
- euler.setTheta(0.5f);
- euler.setPsi(0.6f);
- ASSERT(vectorEqual(Vector3(0.4f, 0.5f, 0.6f), euler));
-
- printf("PASS\n");
- return 0;
-}
-
-} // namespace math
diff --git a/src/modules/mathlib/math/Matrix.cpp b/src/modules/mathlib/math/Matrix.cpp
deleted file mode 100644
index ebd1aeda3..000000000
--- a/src/modules/mathlib/math/Matrix.cpp
+++ /dev/null
@@ -1,193 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Matrix.cpp
- *
- * matrix code
- */
-
-#include "test/test.hpp"
-#include <math.h>
-
-#include "Matrix.hpp"
-
-namespace math
-{
-
-static const float data_testA[] = {
- 1, 2, 3,
- 4, 5, 6
-};
-static Matrix testA(2, 3, data_testA);
-
-static const float data_testB[] = {
- 0, 1, 3,
- 7, -1, 2
-};
-static Matrix testB(2, 3, data_testB);
-
-static const float data_testC[] = {
- 0, 1,
- 2, 1,
- 3, 2
-};
-static Matrix testC(3, 2, data_testC);
-
-static const float data_testD[] = {
- 0, 1, 2,
- 2, 1, 4,
- 5, 2, 0
-};
-static Matrix testD(3, 3, data_testD);
-
-static const float data_testE[] = {
- 1, -1, 2,
- 0, 2, 3,
- 2, -1, 1
-};
-static Matrix testE(3, 3, data_testE);
-
-static const float data_testF[] = {
- 3.777e006f, 2.915e007f, 0.000e000f,
- 2.938e007f, 2.267e008f, 0.000e000f,
- 0.000e000f, 0.000e000f, 6.033e008f
-};
-static Matrix testF(3, 3, data_testF);
-
-int __EXPORT matrixTest()
-{
- matrixAddTest();
- matrixSubTest();
- matrixMultTest();
- matrixInvTest();
- matrixDivTest();
- return 0;
-}
-
-int matrixAddTest()
-{
- printf("Test Matrix Add\t\t: ");
- Matrix r = testA + testB;
- float data_test[] = {
- 1.0f, 3.0f, 6.0f,
- 11.0f, 4.0f, 8.0f
- };
- ASSERT(matrixEqual(Matrix(2, 3, data_test), r));
- printf("PASS\n");
- return 0;
-}
-
-int matrixSubTest()
-{
- printf("Test Matrix Sub\t\t: ");
- Matrix r = testA - testB;
- float data_test[] = {
- 1.0f, 1.0f, 0.0f,
- -3.0f, 6.0f, 4.0f
- };
- ASSERT(matrixEqual(Matrix(2, 3, data_test), r));
- printf("PASS\n");
- return 0;
-}
-
-int matrixMultTest()
-{
- printf("Test Matrix Mult\t: ");
- Matrix r = testC * testB;
- float data_test[] = {
- 7.0f, -1.0f, 2.0f,
- 7.0f, 1.0f, 8.0f,
- 14.0f, 1.0f, 13.0f
- };
- ASSERT(matrixEqual(Matrix(3, 3, data_test), r));
- printf("PASS\n");
- return 0;
-}
-
-int matrixInvTest()
-{
- printf("Test Matrix Inv\t\t: ");
- Matrix origF = testF;
- Matrix r = testF.inverse();
- float data_test[] = {
- -0.0012518f, 0.0001610f, 0.0000000f,
- 0.0001622f, -0.0000209f, 0.0000000f,
- 0.0000000f, 0.0000000f, 1.6580e-9f
- };
- ASSERT(matrixEqual(Matrix(3, 3, data_test), r));
- // make sure F in unchanged
- ASSERT(matrixEqual(origF, testF));
- printf("PASS\n");
- return 0;
-}
-
-int matrixDivTest()
-{
- printf("Test Matrix Div\t\t: ");
- Matrix r = testD / testE;
- float data_test[] = {
- 0.2222222f, 0.5555556f, -0.1111111f,
- 0.0f, 1.0f, 1.0,
- -4.1111111f, 1.2222222f, 4.5555556f
- };
- ASSERT(matrixEqual(Matrix(3, 3, data_test), r));
- printf("PASS\n");
- return 0;
-}
-
-bool matrixEqual(const Matrix &a, const Matrix &b, float eps)
-{
- if (a.getRows() != b.getRows()) {
- printf("row number not equal a: %d, b:%d\n", a.getRows(), b.getRows());
- return false;
-
- } else if (a.getCols() != b.getCols()) {
- printf("column number not equal a: %d, b:%d\n", a.getCols(), b.getCols());
- return false;
- }
-
- bool ret = true;
-
- for (size_t i = 0; i < a.getRows(); i++)
- for (size_t j = 0; j < a.getCols(); j++) {
- if (!equal(a(i, j), b(i, j), eps)) {
- printf("element mismatch (%d, %d)\n", i, j);
- ret = false;
- }
- }
-
- return ret;
-}
-
-} // namespace math
diff --git a/src/modules/mathlib/math/Quaternion.cpp b/src/modules/mathlib/math/Quaternion.cpp
deleted file mode 100644
index 02fec4ca6..000000000
--- a/src/modules/mathlib/math/Quaternion.cpp
+++ /dev/null
@@ -1,174 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Quaternion.cpp
- *
- * math vector
- */
-
-#include "test/test.hpp"
-
-
-#include "Quaternion.hpp"
-#include "Dcm.hpp"
-#include "EulerAngles.hpp"
-
-namespace math
-{
-
-Quaternion::Quaternion() :
- Vector(4)
-{
- setA(1.0f);
- setB(0.0f);
- setC(0.0f);
- setD(0.0f);
-}
-
-Quaternion::Quaternion(float a, float b,
- float c, float d) :
- Vector(4)
-{
- setA(a);
- setB(b);
- setC(c);
- setD(d);
-}
-
-Quaternion::Quaternion(const float *data) :
- Vector(4, data)
-{
-}
-
-Quaternion::Quaternion(const Vector &v) :
- Vector(v)
-{
-}
-
-Quaternion::Quaternion(const Dcm &dcm) :
- Vector(4)
-{
- // avoiding singularities by not using
- // division equations
- setA(0.5 * sqrt(1.0 +
- double(dcm(0, 0) + dcm(1, 1) + dcm(2, 2))));
- setB(0.5 * sqrt(1.0 +
- double(dcm(0, 0) - dcm(1, 1) - dcm(2, 2))));
- setC(0.5 * sqrt(1.0 +
- double(-dcm(0, 0) + dcm(1, 1) - dcm(2, 2))));
- setD(0.5 * sqrt(1.0 +
- double(-dcm(0, 0) - dcm(1, 1) + dcm(2, 2))));
-}
-
-Quaternion::Quaternion(const EulerAngles &euler) :
- Vector(4)
-{
- double cosPhi_2 = cos(double(euler.getPhi()) / 2.0);
- double sinPhi_2 = sin(double(euler.getPhi()) / 2.0);
- double cosTheta_2 = cos(double(euler.getTheta()) / 2.0);
- double sinTheta_2 = sin(double(euler.getTheta()) / 2.0);
- double cosPsi_2 = cos(double(euler.getPsi()) / 2.0);
- double sinPsi_2 = sin(double(euler.getPsi()) / 2.0);
- setA(cosPhi_2 * cosTheta_2 * cosPsi_2 +
- sinPhi_2 * sinTheta_2 * sinPsi_2);
- setB(sinPhi_2 * cosTheta_2 * cosPsi_2 -
- cosPhi_2 * sinTheta_2 * sinPsi_2);
- setC(cosPhi_2 * sinTheta_2 * cosPsi_2 +
- sinPhi_2 * cosTheta_2 * sinPsi_2);
- setD(cosPhi_2 * cosTheta_2 * sinPsi_2 -
- sinPhi_2 * sinTheta_2 * cosPsi_2);
-}
-
-Quaternion::Quaternion(const Quaternion &right) :
- Vector(right)
-{
-}
-
-Quaternion::~Quaternion()
-{
-}
-
-Vector Quaternion::derivative(const Vector &w)
-{
-#ifdef QUATERNION_ASSERT
- ASSERT(w.getRows() == 3);
-#endif
- float dataQ[] = {
- getA(), -getB(), -getC(), -getD(),
- getB(), getA(), -getD(), getC(),
- getC(), getD(), getA(), -getB(),
- getD(), -getC(), getB(), getA()
- };
- Vector v(4);
- v(0) = 0.0f;
- v(1) = w(0);
- v(2) = w(1);
- v(3) = w(2);
- Matrix Q(4, 4, dataQ);
- return Q * v * 0.5f;
-}
-
-int __EXPORT quaternionTest()
-{
- printf("Test Quaternion\t\t: ");
- // test default ctor
- Quaternion q;
- ASSERT(equal(q.getA(), 1.0f));
- ASSERT(equal(q.getB(), 0.0f));
- ASSERT(equal(q.getC(), 0.0f));
- ASSERT(equal(q.getD(), 0.0f));
- // test float ctor
- q = Quaternion(0.1825742f, 0.3651484f, 0.5477226f, 0.7302967f);
- ASSERT(equal(q.getA(), 0.1825742f));
- ASSERT(equal(q.getB(), 0.3651484f));
- ASSERT(equal(q.getC(), 0.5477226f));
- ASSERT(equal(q.getD(), 0.7302967f));
- // test euler ctor
- q = Quaternion(EulerAngles(0.1f, 0.2f, 0.3f));
- ASSERT(vectorEqual(q, Quaternion(0.983347f, 0.034271f, 0.106021f, 0.143572f)));
- // test dcm ctor
- q = Quaternion(Dcm());
- ASSERT(vectorEqual(q, Quaternion(1.0f, 0.0f, 0.0f, 0.0f)));
- // TODO test derivative
- // test accessors
- q.setA(0.1f);
- q.setB(0.2f);
- q.setC(0.3f);
- q.setD(0.4f);
- ASSERT(vectorEqual(q, Quaternion(0.1f, 0.2f, 0.3f, 0.4f)));
- printf("PASS\n");
- return 0;
-}
-
-} // namespace math
diff --git a/src/modules/mathlib/math/arm/Matrix.hpp b/src/modules/mathlib/math/arm/Matrix.hpp
deleted file mode 100644
index 715fd3a5e..000000000
--- a/src/modules/mathlib/math/arm/Matrix.hpp
+++ /dev/null
@@ -1,292 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Matrix.h
- *
- * matrix code
- */
-
-#pragma once
-
-
-#include <inttypes.h>
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdio.h>
-#include <math.h>
-
-#include "../Vector.hpp"
-#include "../Matrix.hpp"
-
-// arm specific
-#include "../../CMSIS/Include/arm_math.h"
-
-namespace math
-{
-
-class __EXPORT Matrix
-{
-public:
- // constructor
- Matrix(size_t rows, size_t cols) :
- _matrix() {
- arm_mat_init_f32(&_matrix,
- rows, cols,
- (float *)calloc(rows * cols, sizeof(float)));
- }
- Matrix(size_t rows, size_t cols, const float *data) :
- _matrix() {
- arm_mat_init_f32(&_matrix,
- rows, cols,
- (float *)malloc(rows * cols * sizeof(float)));
- memcpy(getData(), data, getSize());
- }
- // deconstructor
- virtual ~Matrix() {
- delete [] _matrix.pData;
- }
- // copy constructor (deep)
- Matrix(const Matrix &right) :
- _matrix() {
- arm_mat_init_f32(&_matrix,
- right.getRows(), right.getCols(),
- (float *)malloc(right.getRows()*
- right.getCols()*sizeof(float)));
- memcpy(getData(), right.getData(),
- getSize());
- }
- // assignment
- inline Matrix &operator=(const Matrix &right) {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == right.getRows());
- ASSERT(getCols() == right.getCols());
-#endif
-
- if (this != &right) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
-
- return *this;
- }
- // element accessors
- inline float &operator()(size_t i, size_t j) {
-#ifdef MATRIX_ASSERT
- ASSERT(i < getRows());
- ASSERT(j < getCols());
-#endif
- return getData()[i * getCols() + j];
- }
- inline const float &operator()(size_t i, size_t j) const {
-#ifdef MATRIX_ASSERT
- ASSERT(i < getRows());
- ASSERT(j < getCols());
-#endif
- return getData()[i * getCols() + j];
- }
- // output
- inline void print() const {
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- float sig;
- int exp;
- float num = (*this)(i, j);
- float2SigExp(num, sig, exp);
- printf("%6.3fe%03.3d,", (double)sig, exp);
- }
-
- printf("\n");
- }
- }
- // boolean ops
- inline bool operator==(const Matrix &right) const {
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- if (fabsf((*this)(i, j) - right(i, j)) > 1e-30f)
- return false;
- }
- }
-
- return true;
- }
- // scalar ops
- inline Matrix operator+(float right) const {
- Matrix result(getRows(), getCols());
- arm_offset_f32((float *)getData(), right,
- (float *)result.getData(), getRows()*getCols());
- return result;
- }
- inline Matrix operator-(float right) const {
- Matrix result(getRows(), getCols());
- arm_offset_f32((float *)getData(), -right,
- (float *)result.getData(), getRows()*getCols());
- return result;
- }
- inline Matrix operator*(float right) const {
- Matrix result(getRows(), getCols());
- arm_mat_scale_f32(&_matrix, right,
- &(result._matrix));
- return result;
- }
- inline Matrix operator/(float right) const {
- Matrix result(getRows(), getCols());
- arm_mat_scale_f32(&_matrix, 1.0f / right,
- &(result._matrix));
- return result;
- }
- // vector ops
- inline Vector operator*(const Vector &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getCols() == right.getRows());
-#endif
- Matrix resultMat = (*this) *
- Matrix(right.getRows(), 1, right.getData());
- return Vector(getRows(), resultMat.getData());
- }
- // matrix ops
- inline Matrix operator+(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == right.getRows());
- ASSERT(getCols() == right.getCols());
-#endif
- Matrix result(getRows(), getCols());
- arm_mat_add_f32(&_matrix, &(right._matrix),
- &(result._matrix));
- return result;
- }
- inline Matrix operator-(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == right.getRows());
- ASSERT(getCols() == right.getCols());
-#endif
- Matrix result(getRows(), getCols());
- arm_mat_sub_f32(&_matrix, &(right._matrix),
- &(result._matrix));
- return result;
- }
- inline Matrix operator*(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getCols() == right.getRows());
-#endif
- Matrix result(getRows(), right.getCols());
- arm_mat_mult_f32(&_matrix, &(right._matrix),
- &(result._matrix));
- return result;
- }
- inline Matrix operator/(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(right.getRows() == right.getCols());
- ASSERT(getCols() == right.getCols());
-#endif
- return (*this) * right.inverse();
- }
- // other functions
- inline Matrix transpose() const {
- Matrix result(getCols(), getRows());
- arm_mat_trans_f32(&_matrix, &(result._matrix));
- return result;
- }
- inline void swapRows(size_t a, size_t b) {
- if (a == b) return;
-
- for (size_t j = 0; j < getCols(); j++) {
- float tmp = (*this)(a, j);
- (*this)(a, j) = (*this)(b, j);
- (*this)(b, j) = tmp;
- }
- }
- inline void swapCols(size_t a, size_t b) {
- if (a == b) return;
-
- for (size_t i = 0; i < getRows(); i++) {
- float tmp = (*this)(i, a);
- (*this)(i, a) = (*this)(i, b);
- (*this)(i, b) = tmp;
- }
- }
- /**
- * inverse based on LU factorization with partial pivotting
- */
- Matrix inverse() const {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == getCols());
-#endif
- Matrix result(getRows(), getCols());
- Matrix work = (*this);
- arm_mat_inverse_f32(&(work._matrix),
- &(result._matrix));
- return result;
- }
- inline void setAll(const float &val) {
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- (*this)(i, j) = val;
- }
- }
- }
- inline void set(const float *data) {
- memcpy(getData(), data, getSize());
- }
- inline size_t getRows() const { return _matrix.numRows; }
- inline size_t getCols() const { return _matrix.numCols; }
- inline static Matrix identity(size_t size) {
- Matrix result(size, size);
-
- for (size_t i = 0; i < size; i++) {
- result(i, i) = 1.0f;
- }
-
- return result;
- }
- inline static Matrix zero(size_t size) {
- Matrix result(size, size);
- result.setAll(0.0f);
- return result;
- }
- inline static Matrix zero(size_t m, size_t n) {
- Matrix result(m, n);
- result.setAll(0.0f);
- return result;
- }
-protected:
- inline size_t getSize() const { return sizeof(float) * getRows() * getCols(); }
- inline float *getData() { return _matrix.pData; }
- inline const float *getData() const { return _matrix.pData; }
- inline void setData(float *data) { _matrix.pData = data; }
-private:
- arm_matrix_instance_f32 _matrix;
-};
-
-} // namespace math
diff --git a/src/modules/mathlib/math/arm/Vector.hpp b/src/modules/mathlib/math/arm/Vector.hpp
deleted file mode 100644
index 58d51107d..000000000
--- a/src/modules/mathlib/math/arm/Vector.hpp
+++ /dev/null
@@ -1,220 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Vector.h
- *
- * math vector
- */
-
-#pragma once
-
-#include <inttypes.h>
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdio.h>
-#include <math.h>
-
-#include "../Vector.hpp"
-#include "../test/test.hpp"
-
-// arm specific
-#include "../../CMSIS/Include/arm_math.h"
-
-namespace math
-{
-
-class __EXPORT Vector
-{
-public:
- // constructor
- Vector(size_t rows) :
- _rows(rows),
- _data((float *)calloc(rows, sizeof(float))) {
- }
- Vector(size_t rows, const float *data) :
- _rows(rows),
- _data((float *)malloc(getSize())) {
- memcpy(getData(), data, getSize());
- }
- // deconstructor
- virtual ~Vector() {
- delete [] getData();
- }
- // copy constructor (deep)
- Vector(const Vector &right) :
- _rows(right.getRows()),
- _data((float *)malloc(getSize())) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
- // assignment
- inline Vector &operator=(const Vector &right) {
-#ifdef VECTOR_ASSERT
- ASSERT(getRows() == right.getRows());
-#endif
-
- if (this != &right) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
-
- return *this;
- }
- // element accessors
- inline float &operator()(size_t i) {
-#ifdef VECTOR_ASSERT
- ASSERT(i < getRows());
-#endif
- return getData()[i];
- }
- inline const float &operator()(size_t i) const {
-#ifdef VECTOR_ASSERT
- ASSERT(i < getRows());
-#endif
- return getData()[i];
- }
- // output
- inline void print() const {
- for (size_t i = 0; i < getRows(); i++) {
- float sig;
- int exp;
- float num = (*this)(i);
- float2SigExp(num, sig, exp);
- printf("%6.3fe%03.3d,", (double)sig, exp);
- }
-
- printf("\n");
- }
- // boolean ops
- inline bool operator==(const Vector &right) const {
- for (size_t i = 0; i < getRows(); i++) {
- if (fabsf(((*this)(i) - right(i))) > 1e-30f)
- return false;
- }
-
- return true;
- }
- // scalar ops
- inline Vector operator+(float right) const {
- Vector result(getRows());
- arm_offset_f32((float *)getData(),
- right, result.getData(),
- getRows());
- return result;
- }
- inline Vector operator-(float right) const {
- Vector result(getRows());
- arm_offset_f32((float *)getData(),
- -right, result.getData(),
- getRows());
- return result;
- }
- inline Vector operator*(float right) const {
- Vector result(getRows());
- arm_scale_f32((float *)getData(),
- right, result.getData(),
- getRows());
- return result;
- }
- inline Vector operator/(float right) const {
- Vector result(getRows());
- arm_scale_f32((float *)getData(),
- 1.0f / right, result.getData(),
- getRows());
- return result;
- }
- // vector ops
- inline Vector operator+(const Vector &right) const {
-#ifdef VECTOR_ASSERT
- ASSERT(getRows() == right.getRows());
-#endif
- Vector result(getRows());
- arm_add_f32((float *)getData(),
- (float *)right.getData(),
- result.getData(),
- getRows());
- return result;
- }
- inline Vector operator-(const Vector &right) const {
-#ifdef VECTOR_ASSERT
- ASSERT(getRows() == right.getRows());
-#endif
- Vector result(getRows());
- arm_sub_f32((float *)getData(),
- (float *)right.getData(),
- result.getData(),
- getRows());
- return result;
- }
- // other functions
- inline float dot(const Vector &right) {
- float result = 0;
- arm_dot_prod_f32((float *)getData(),
- (float *)right.getData(),
- getRows(),
- &result);
- return result;
- }
- inline float norm() {
- return sqrtf(dot(*this));
- }
- inline Vector unit() {
- return (*this) / norm();
- }
- inline static Vector zero(size_t rows) {
- Vector result(rows);
- // calloc returns zeroed memory
- return result;
- }
- inline void setAll(const float &val) {
- for (size_t i = 0; i < getRows(); i++) {
- (*this)(i) = val;
- }
- }
- inline void set(const float *data) {
- memcpy(getData(), data, getSize());
- }
- inline size_t getRows() const { return _rows; }
- inline const float *getData() const { return _data; }
-protected:
- inline size_t getSize() const { return sizeof(float) * getRows(); }
- inline float *getData() { return _data; }
- inline void setData(float *data) { _data = data; }
-private:
- size_t _rows;
- float *_data;
-};
-
-} // math
diff --git a/src/modules/mathlib/math/generic/Matrix.hpp b/src/modules/mathlib/math/generic/Matrix.hpp
deleted file mode 100644
index 5601a3447..000000000
--- a/src/modules/mathlib/math/generic/Matrix.hpp
+++ /dev/null
@@ -1,437 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Matrix.h
- *
- * matrix code
- */
-
-#pragma once
-
-
-#include <inttypes.h>
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdio.h>
-#include <math.h>
-
-#include "../Vector.hpp"
-#include "../Matrix.hpp"
-
-namespace math
-{
-
-class __EXPORT Matrix
-{
-public:
- // constructor
- Matrix(size_t rows, size_t cols) :
- _rows(rows),
- _cols(cols),
- _data((float *)calloc(rows *cols, sizeof(float))) {
- }
- Matrix(size_t rows, size_t cols, const float *data) :
- _rows(rows),
- _cols(cols),
- _data((float *)malloc(getSize())) {
- memcpy(getData(), data, getSize());
- }
- // deconstructor
- virtual ~Matrix() {
- delete [] getData();
- }
- // copy constructor (deep)
- Matrix(const Matrix &right) :
- _rows(right.getRows()),
- _cols(right.getCols()),
- _data((float *)malloc(getSize())) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
- // assignment
- inline Matrix &operator=(const Matrix &right) {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == right.getRows());
- ASSERT(getCols() == right.getCols());
-#endif
-
- if (this != &right) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
-
- return *this;
- }
- // element accessors
- inline float &operator()(size_t i, size_t j) {
-#ifdef MATRIX_ASSERT
- ASSERT(i < getRows());
- ASSERT(j < getCols());
-#endif
- return getData()[i * getCols() + j];
- }
- inline const float &operator()(size_t i, size_t j) const {
-#ifdef MATRIX_ASSERT
- ASSERT(i < getRows());
- ASSERT(j < getCols());
-#endif
- return getData()[i * getCols() + j];
- }
- // output
- inline void print() const {
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- float sig;
- int exp;
- float num = (*this)(i, j);
- float2SigExp(num, sig, exp);
- printf("%6.3fe%03.3d,", (double)sig, exp);
- }
-
- printf("\n");
- }
- }
- // boolean ops
- inline bool operator==(const Matrix &right) const {
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- if (fabsf((*this)(i, j) - right(i, j)) > 1e-30f)
- return false;
- }
- }
-
- return true;
- }
- // scalar ops
- inline Matrix operator+(const float &right) const {
- Matrix result(getRows(), getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i, j) = (*this)(i, j) + right;
- }
- }
-
- return result;
- }
- inline Matrix operator-(const float &right) const {
- Matrix result(getRows(), getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i, j) = (*this)(i, j) - right;
- }
- }
-
- return result;
- }
- inline Matrix operator*(const float &right) const {
- Matrix result(getRows(), getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i, j) = (*this)(i, j) * right;
- }
- }
-
- return result;
- }
- inline Matrix operator/(const float &right) const {
- Matrix result(getRows(), getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i, j) = (*this)(i, j) / right;
- }
- }
-
- return result;
- }
- // vector ops
- inline Vector operator*(const Vector &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getCols() == right.getRows());
-#endif
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i) += (*this)(i, j) * right(j);
- }
- }
-
- return result;
- }
- // matrix ops
- inline Matrix operator+(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == right.getRows());
- ASSERT(getCols() == right.getCols());
-#endif
- Matrix result(getRows(), getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i, j) = (*this)(i, j) + right(i, j);
- }
- }
-
- return result;
- }
- inline Matrix operator-(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == right.getRows());
- ASSERT(getCols() == right.getCols());
-#endif
- Matrix result(getRows(), getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(i, j) = (*this)(i, j) - right(i, j);
- }
- }
-
- return result;
- }
- inline Matrix operator*(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(getCols() == right.getRows());
-#endif
- Matrix result(getRows(), right.getCols());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < right.getCols(); j++) {
- for (size_t k = 0; k < right.getRows(); k++) {
- result(i, j) += (*this)(i, k) * right(k, j);
- }
- }
- }
-
- return result;
- }
- inline Matrix operator/(const Matrix &right) const {
-#ifdef MATRIX_ASSERT
- ASSERT(right.getRows() == right.getCols());
- ASSERT(getCols() == right.getCols());
-#endif
- return (*this) * right.inverse();
- }
- // other functions
- inline Matrix transpose() const {
- Matrix result(getCols(), getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- result(j, i) = (*this)(i, j);
- }
- }
-
- return result;
- }
- inline void swapRows(size_t a, size_t b) {
- if (a == b) return;
-
- for (size_t j = 0; j < getCols(); j++) {
- float tmp = (*this)(a, j);
- (*this)(a, j) = (*this)(b, j);
- (*this)(b, j) = tmp;
- }
- }
- inline void swapCols(size_t a, size_t b) {
- if (a == b) return;
-
- for (size_t i = 0; i < getRows(); i++) {
- float tmp = (*this)(i, a);
- (*this)(i, a) = (*this)(i, b);
- (*this)(i, b) = tmp;
- }
- }
- /**
- * inverse based on LU factorization with partial pivotting
- */
- Matrix inverse() const {
-#ifdef MATRIX_ASSERT
- ASSERT(getRows() == getCols());
-#endif
- size_t N = getRows();
- Matrix L = identity(N);
- const Matrix &A = (*this);
- Matrix U = A;
- Matrix P = identity(N);
-
- //printf("A:\n"); A.print();
-
- // for all diagonal elements
- for (size_t n = 0; n < N; n++) {
-
- // if diagonal is zero, swap with row below
- if (fabsf(U(n, n)) < 1e-8f) {
- //printf("trying pivot for row %d\n",n);
- for (size_t i = 0; i < N; i++) {
- if (i == n) continue;
-
- //printf("\ttrying row %d\n",i);
- if (fabsf(U(i, n)) > 1e-8f) {
- //printf("swapped %d\n",i);
- U.swapRows(i, n);
- P.swapRows(i, n);
- }
- }
- }
-
-#ifdef MATRIX_ASSERT
- //printf("A:\n"); A.print();
- //printf("U:\n"); U.print();
- //printf("P:\n"); P.print();
- //fflush(stdout);
- ASSERT(fabsf(U(n, n)) > 1e-8f);
-#endif
-
- // failsafe, return zero matrix
- if (fabsf(U(n, n)) < 1e-8f) {
- return Matrix::zero(n);
- }
-
- // for all rows below diagonal
- for (size_t i = (n + 1); i < N; i++) {
- L(i, n) = U(i, n) / U(n, n);
-
- // add i-th row and n-th row
- // multiplied by: -a(i,n)/a(n,n)
- for (size_t k = n; k < N; k++) {
- U(i, k) -= L(i, n) * U(n, k);
- }
- }
- }
-
- //printf("L:\n"); L.print();
- //printf("U:\n"); U.print();
-
- // solve LY=P*I for Y by forward subst
- Matrix Y = P;
-
- // for all columns of Y
- for (size_t c = 0; c < N; c++) {
- // for all rows of L
- for (size_t i = 0; i < N; i++) {
- // for all columns of L
- for (size_t j = 0; j < i; j++) {
- // for all existing y
- // subtract the component they
- // contribute to the solution
- Y(i, c) -= L(i, j) * Y(j, c);
- }
-
- // divide by the factor
- // on current
- // term to be solved
- // Y(i,c) /= L(i,i);
- // but L(i,i) = 1.0
- }
- }
-
- //printf("Y:\n"); Y.print();
-
- // solve Ux=y for x by back subst
- Matrix X = Y;
-
- // for all columns of X
- for (size_t c = 0; c < N; c++) {
- // for all rows of U
- for (size_t k = 0; k < N; k++) {
- // have to go in reverse order
- size_t i = N - 1 - k;
-
- // for all columns of U
- for (size_t j = i + 1; j < N; j++) {
- // for all existing x
- // subtract the component they
- // contribute to the solution
- X(i, c) -= U(i, j) * X(j, c);
- }
-
- // divide by the factor
- // on current
- // term to be solved
- X(i, c) /= U(i, i);
- }
- }
-
- //printf("X:\n"); X.print();
- return X;
- }
- inline void setAll(const float &val) {
- for (size_t i = 0; i < getRows(); i++) {
- for (size_t j = 0; j < getCols(); j++) {
- (*this)(i, j) = val;
- }
- }
- }
- inline void set(const float *data) {
- memcpy(getData(), data, getSize());
- }
- inline size_t getRows() const { return _rows; }
- inline size_t getCols() const { return _cols; }
- inline static Matrix identity(size_t size) {
- Matrix result(size, size);
-
- for (size_t i = 0; i < size; i++) {
- result(i, i) = 1.0f;
- }
-
- return result;
- }
- inline static Matrix zero(size_t size) {
- Matrix result(size, size);
- result.setAll(0.0f);
- return result;
- }
- inline static Matrix zero(size_t m, size_t n) {
- Matrix result(m, n);
- result.setAll(0.0f);
- return result;
- }
-protected:
- inline size_t getSize() const { return sizeof(float) * getRows() * getCols(); }
- inline float *getData() { return _data; }
- inline const float *getData() const { return _data; }
- inline void setData(float *data) { _data = data; }
-private:
- size_t _rows;
- size_t _cols;
- float *_data;
-};
-
-} // namespace math
diff --git a/src/modules/mathlib/math/generic/Vector.hpp b/src/modules/mathlib/math/generic/Vector.hpp
deleted file mode 100644
index 1a7363779..000000000
--- a/src/modules/mathlib/math/generic/Vector.hpp
+++ /dev/null
@@ -1,227 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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 Vector.h
- *
- * math vector
- */
-
-#pragma once
-
-#include <inttypes.h>
-#include <assert.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdio.h>
-#include <math.h>
-
-#include "../Vector.hpp"
-
-namespace math
-{
-
-class __EXPORT Vector
-{
-public:
- // constructor
- Vector(size_t rows) :
- _rows(rows),
- _data((float *)calloc(rows, sizeof(float))) {
- }
- Vector(size_t rows, const float *data) :
- _rows(rows),
- _data((float *)malloc(getSize())) {
- memcpy(getData(), data, getSize());
- }
- // deconstructor
- virtual ~Vector() {
- delete [] getData();
- }
- // copy constructor (deep)
- Vector(const Vector &right) :
- _rows(right.getRows()),
- _data((float *)malloc(getSize())) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
- // assignment
- inline Vector &operator=(const Vector &right) {
-#ifdef VECTOR_ASSERT
- ASSERT(getRows() == right.getRows());
-#endif
-
- if (this != &right) {
- memcpy(getData(), right.getData(),
- right.getSize());
- }
-
- return *this;
- }
- // element accessors
- inline float &operator()(size_t i) {
-#ifdef VECTOR_ASSERT
- ASSERT(i < getRows());
-#endif
- return getData()[i];
- }
- inline const float &operator()(size_t i) const {
-#ifdef VECTOR_ASSERT
- ASSERT(i < getRows());
-#endif
- return getData()[i];
- }
- // output
- inline void print() const {
- for (size_t i = 0; i < getRows(); i++) {
- float sig;
- int exp;
- float num = (*this)(i);
- float2SigExp(num, sig, exp);
- printf("%6.3fe%03.3d,", (double)sig, exp);
- }
-
- printf("\n");
- }
- // boolean ops
- inline bool operator==(const Vector &right) const {
- for (size_t i = 0; i < getRows(); i++) {
- if (fabsf(((*this)(i) - right(i))) > 1e-30f)
- return false;
- }
-
- return true;
- }
- // scalar ops
- inline Vector operator+(const float &right) const {
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = (*this)(i) + right;
- }
-
- return result;
- }
- inline Vector operator-(const float &right) const {
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = (*this)(i) - right;
- }
-
- return result;
- }
- inline Vector operator*(const float &right) const {
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = (*this)(i) * right;
- }
-
- return result;
- }
- inline Vector operator/(const float &right) const {
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = (*this)(i) / right;
- }
-
- return result;
- }
- // vector ops
- inline Vector operator+(const Vector &right) const {
-#ifdef VECTOR_ASSERT
- ASSERT(getRows() == right.getRows());
-#endif
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = (*this)(i) + right(i);
- }
-
- return result;
- }
- inline Vector operator-(const Vector &right) const {
-#ifdef VECTOR_ASSERT
- ASSERT(getRows() == right.getRows());
-#endif
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = (*this)(i) - right(i);
- }
-
- return result;
- }
- // other functions
- inline float dot(const Vector &right) {
- float result = 0;
-
- for (size_t i = 0; i < getRows(); i++) {
- result += (*this)(i) * (*this)(i);
- }
-
- return result;
- }
- inline float norm() {
- return sqrtf(dot(*this));
- }
- inline Vector unit() {
- return (*this) / norm();
- }
- inline static Vector zero(size_t rows) {
- Vector result(rows);
- // calloc returns zeroed memory
- return result;
- }
- inline void setAll(const float &val) {
- for (size_t i = 0; i < getRows(); i++) {
- (*this)(i) = val;
- }
- }
- inline void set(const float *data) {
- memcpy(getData(), data, getSize());
- }
- inline size_t getRows() const { return _rows; }
-protected:
- inline size_t getSize() const { return sizeof(float) * getRows(); }
- inline float *getData() { return _data; }
- inline const float *getData() const { return _data; }
- inline void setData(float *data) { _data = data; }
-private:
- size_t _rows;
- float *_data;
-};
-
-} // math
diff --git a/src/modules/mathlib/math/nasa_rotation_def.pdf b/src/modules/mathlib/math/nasa_rotation_def.pdf
deleted file mode 100644
index eb67a4bfc..000000000
--- a/src/modules/mathlib/math/nasa_rotation_def.pdf
+++ /dev/null
Binary files differ
diff --git a/src/modules/mathlib/math/test_math.sce b/src/modules/mathlib/math/test_math.sce
deleted file mode 100644
index c3fba4729..000000000
--- a/src/modules/mathlib/math/test_math.sce
+++ /dev/null
@@ -1,63 +0,0 @@
-clc
-clear
-function out = float_truncate(in, digits)
- out = round(in*10^digits)
- out = out/10^digits
-endfunction
-
-phi = 0.1
-theta = 0.2
-psi = 0.3
-
-cosPhi = cos(phi)
-cosPhi_2 = cos(phi/2)
-sinPhi = sin(phi)
-sinPhi_2 = sin(phi/2)
-
-cosTheta = cos(theta)
-cosTheta_2 = cos(theta/2)
-sinTheta = sin(theta)
-sinTheta_2 = sin(theta/2)
-
-cosPsi = cos(psi)
-cosPsi_2 = cos(psi/2)
-sinPsi = sin(psi)
-sinPsi_2 = sin(psi/2)
-
-C_nb = [cosTheta*cosPsi, -cosPhi*sinPsi + sinPhi*sinTheta*cosPsi, sinPhi*sinPsi + cosPhi*sinTheta*cosPsi;
- cosTheta*sinPsi, cosPhi*cosPsi + sinPhi*sinTheta*sinPsi, -sinPhi*cosPsi + cosPhi*sinTheta*sinPsi;
- -sinTheta, sinPhi*cosTheta, cosPhi*cosTheta]
-
-disp(C_nb)
-//C_nb = float_truncate(C_nb,3)
-//disp(C_nb)
-
-theta = asin(-C_nb(3,1))
-phi = atan(C_nb(3,2), C_nb(3,3))
-psi = atan(C_nb(2,1), C_nb(1,1))
-printf('phi %f\n', phi)
-printf('theta %f\n', theta)
-printf('psi %f\n', psi)
-
-q = [cosPhi_2*cosTheta_2*cosPsi_2 + sinPhi_2*sinTheta_2*sinPsi_2;
- sinPhi_2*cosTheta_2*cosPsi_2 - cosPhi_2*sinTheta_2*sinPsi_2;
- cosPhi_2*sinTheta_2*cosPsi_2 + sinPhi_2*cosTheta_2*sinPsi_2;
- cosPhi_2*cosTheta_2*sinPsi_2 - sinPhi_2*sinTheta_2*cosPsi_2]
-
-//q = float_truncate(q,3)
-
-a = q(1)
-b = q(2)
-c = q(3)
-d = q(4)
-printf('q: %f %f %f %f\n', a, b, c, d)
-a2 = a*a
-b2 = b*b
-c2 = c*c
-d2 = d*d
-
-C2_nb = [a2 + b2 - c2 - d2, 2*(b*c - a*d), 2*(b*d + a*c);
- 2*(b*c + a*d), a2 - b2 + c2 - d2, 2*(c*d - a*b);
- 2*(b*d - a*c), 2*(c*d + a*b), a2 - b2 - c2 + d2]
-
-disp(C2_nb)
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index c72a53fee..20853379d 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -49,7 +49,6 @@
#include <mqueue.h>
#include <string.h>
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
#include <time.h>
#include <float.h>
@@ -65,6 +64,7 @@
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
#include <mavlink/mavlink_log.h>
+#include <commander/px4_custom_mode.h>
#include "waypoints.h"
#include "orb_topics.h"
@@ -144,14 +144,6 @@ set_hil_on_off(bool hil_enabled)
/* Enable HIL */
if (hil_enabled && !mavlink_hil_enabled) {
- /* Advertise topics */
- pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
- pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
-
- /* sensore level hil */
- pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
- pub_hil_gps = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
-
mavlink_hil_enabled = true;
/* ramp up some HIL-related subscriptions */
@@ -190,102 +182,80 @@ set_hil_on_off(bool hil_enabled)
}
void
-get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode)
+get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode)
{
/* reset MAVLink mode bitfield */
- *mavlink_mode = 0;
+ *mavlink_base_mode = 0;
+ *mavlink_custom_mode = 0;
- /* set mode flags independent of system state */
+ /**
+ * Set mode flags
+ **/
/* HIL */
- if (v_status.flag_hil_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_HIL_ENABLED;
+ if (v_status.hil_state == HIL_STATE_ON) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
}
- /* manual input */
- if (v_status.flag_control_manual_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ /* arming state */
+ if (v_status.arming_state == ARMING_STATE_ARMED
+ || v_status.arming_state == ARMING_STATE_ARMED_ERROR) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
- /* attitude or rate control */
- if (v_status.flag_control_attitude_enabled ||
- v_status.flag_control_rates_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
- }
-
- /* vector control */
- if (v_status.flag_control_velocity_enabled ||
- v_status.flag_control_position_enabled) {
- *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
- }
-
- /* autonomous mode */
- if (v_status.state_machine == SYSTEM_STATE_AUTO) {
- *mavlink_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
- }
-
- /* set arming state */
- if (armed.armed) {
- *mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
-
- } else {
- *mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
- }
-
- switch (v_status.state_machine) {
- case SYSTEM_STATE_PREFLIGHT:
- if (v_status.flag_preflight_gyro_calibration ||
- v_status.flag_preflight_mag_calibration ||
- v_status.flag_preflight_accel_calibration) {
- *mavlink_state = MAV_STATE_CALIBRATING;
-
- } else {
- *mavlink_state = MAV_STATE_UNINIT;
+ /* main state */
+ *mavlink_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+ union px4_custom_mode custom_mode;
+ custom_mode.data = 0;
+ if (v_status.main_state == MAIN_STATE_MANUAL) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (v_status.is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
+ } else if (v_status.main_state == MAIN_STATE_SEATBELT) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_SEATBELT;
+ } else if (v_status.main_state == MAIN_STATE_EASY) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_EASY;
+ } else if (v_status.main_state == MAIN_STATE_AUTO) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ if (v_status.navigation_state == NAVIGATION_STATE_AUTO_READY) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LOITER) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_RTL) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LAND) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
}
-
- break;
-
- case SYSTEM_STATE_STANDBY:
- *mavlink_state = MAV_STATE_STANDBY;
- break;
-
- case SYSTEM_STATE_GROUND_READY:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
-
- case SYSTEM_STATE_MANUAL:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
-
- case SYSTEM_STATE_STABILIZED:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
-
- case SYSTEM_STATE_AUTO:
+ }
+ *mavlink_custom_mode = custom_mode.data;
+
+ /**
+ * Set mavlink state
+ **/
+
+ /* set calibration state */
+ if (v_status.arming_state == ARMING_STATE_INIT
+ || v_status.arming_state == ARMING_STATE_IN_AIR_RESTORE
+ || v_status.arming_state == ARMING_STATE_STANDBY_ERROR) { // TODO review
+ *mavlink_state = MAV_STATE_UNINIT;
+ } else if (v_status.arming_state == ARMING_STATE_ARMED) {
*mavlink_state = MAV_STATE_ACTIVE;
- break;
-
- case SYSTEM_STATE_MISSION_ABORT:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_EMCY_LANDING:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_EMCY_CUTOFF:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_GROUND_ERROR:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_REBOOT:
+ } else if (v_status.arming_state == ARMING_STATE_ARMED_ERROR) {
+ *mavlink_state = MAV_STATE_CRITICAL;
+ } else if (v_status.arming_state == ARMING_STATE_STANDBY) {
+ *mavlink_state = MAV_STATE_STANDBY;
+ } else if (v_status.arming_state == ARMING_STATE_REBOOT) {
*mavlink_state = MAV_STATE_POWEROFF;
- break;
+ } else {
+ warnx("Unknown mavlink state");
+ *mavlink_state = MAV_STATE_CRITICAL;
}
-
}
@@ -321,6 +291,9 @@ int set_mavlink_interval_limit(struct mavlink_subscriptions *subs, int mavlink_m
orb_set_interval(subs->act_2_sub, min_interval);
orb_set_interval(subs->act_3_sub, min_interval);
orb_set_interval(subs->actuators_sub, min_interval);
+ orb_set_interval(subs->actuators_effective_sub, min_interval);
+ orb_set_interval(subs->spa_sub, min_interval);
+ orb_set_interval(mavlink_subs.rates_setpoint_sub, min_interval);
break;
case MAVLINK_MSG_ID_MANUAL_CONTROL:
@@ -429,12 +402,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
case 921600: speed = B921600; break;
default:
- fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
+ warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
return -EINVAL;
}
/* open uart */
- printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
+ warnx("UART is %s, baudrate is %d\n", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@@ -442,44 +415,42 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
int termios_state;
*is_usb = false;
- /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */
- if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) {
- /* Back up the original uart configuration to restore it after exit */
- if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
- close(uart);
- return -1;
- }
+ /* Back up the original uart configuration to restore it after exit */
+ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
+ warnx("ERROR get termios config %s: %d\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
- /* Fill the struct for the new configuration */
- tcgetattr(uart, &uart_config);
+ /* Fill the struct for the new configuration */
+ tcgetattr(uart, &uart_config);
- /* Clear ONLCR flag (which appends a CR for every LF) */
- uart_config.c_oflag &= ~ONLCR;
+ /* Clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
+
+ /* USB serial is indicated by /dev/ttyACM0*/
+ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) {
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
close(uart);
return -1;
}
+ }
- if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
- close(uart);
- return -1;
- }
-
- } else {
- *is_usb = true;
+ if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ close(uart);
+ return -1;
}
return uart;
}
void
-mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
+mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length)
{
write(uart, ch, (size_t)(sizeof(uint8_t) * length));
}
@@ -487,7 +458,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
/*
* Internal function to give access to the channel status for each channel
*/
-mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
+extern mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
{
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_status[channel];
@@ -496,7 +467,7 @@ mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
/*
* Internal function to give access to the channel buffer for each channel
*/
-mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
+extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
{
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_buffer[channel];
@@ -545,7 +516,7 @@ void mavlink_update_system(void)
int mavlink_thread_main(int argc, char *argv[])
{
/* initialize mavlink text message buffering */
- mavlink_logbuffer_init(&lb, 5);
+ mavlink_logbuffer_init(&lb, 10);
int ch;
char *device_name = "/dev/ttyS1";
@@ -560,7 +531,7 @@ int mavlink_thread_main(int argc, char *argv[])
case 'b':
baudrate = strtoul(optarg, NULL, 10);
- if (baudrate == 0)
+ if (baudrate < 9600 || baudrate > 921600)
errx(1, "invalid baud rate '%s'", optarg);
break;
@@ -579,6 +550,7 @@ int mavlink_thread_main(int argc, char *argv[])
default:
usage();
+ break;
}
}
@@ -685,24 +657,28 @@ int mavlink_thread_main(int argc, char *argv[])
/* translate the current system state to mavlink state and mode */
uint8_t mavlink_state = 0;
- uint8_t mavlink_mode = 0;
- get_mavlink_mode_and_state(&mavlink_state, &mavlink_mode);
+ uint8_t mavlink_base_mode = 0;
+ uint32_t mavlink_custom_mode = 0;
+ get_mavlink_mode_and_state(&mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
/* send heartbeat */
- mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
+ mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_base_mode, mavlink_custom_mode, mavlink_state);
/* switch HIL mode if required */
- set_hil_on_off(v_status.flag_hil_enabled);
+ if (v_status.hil_state == HIL_STATE_ON)
+ set_hil_on_off(true);
+ else if (v_status.hil_state == HIL_STATE_OFF)
+ set_hil_on_off(false);
/* send status (values already copied in the section above) */
mavlink_msg_sys_status_send(chan,
v_status.onboard_control_sensors_present,
v_status.onboard_control_sensors_enabled,
v_status.onboard_control_sensors_health,
- v_status.load,
- v_status.voltage_battery * 1000.0f,
- v_status.current_battery * 1000.0f,
- v_status.battery_remaining,
+ v_status.load * 1000.0f,
+ v_status.battery_voltage * 1000.0f,
+ v_status.battery_current * 100.0f,
+ v_status.battery_remaining * 100.0f,
v_status.drop_rate_comm,
v_status.errors_comm,
v_status.errors_count1,
@@ -714,21 +690,26 @@ int mavlink_thread_main(int argc, char *argv[])
lowspeed_counter++;
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
+
/* sleep quarter the time */
usleep(25000);
/* check if waypoint has been reached against the last positions */
- mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos);
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
/* sleep quarter the time */
usleep(25000);
/* send parameters at 20 Hz (if queued for sending) */
mavlink_pm_queued_send();
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
/* sleep quarter the time */
usleep(25000);
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos, &nav_cap);
+
if (baudrate > 57600) {
mavlink_pm_queued_send();
}
@@ -755,12 +736,14 @@ int mavlink_thread_main(int argc, char *argv[])
pthread_join(uorb_receive_thread, NULL);
/* Reset the UART flags to original state */
- if (!usb_uart)
- tcsetattr(uart, TCSANOW, &uart_config_original);
+ tcsetattr(uart, TCSANOW, &uart_config_original);
+
+ /* destroy log buffer */
+ //mavlink_logbuffer_destroy(&lb);
thread_running = false;
- exit(0);
+ return 0;
}
static void
@@ -784,7 +767,7 @@ int mavlink_main(int argc, char *argv[])
/* this is not an error */
if (thread_running)
- errx(0, "mavlink already running\n");
+ errx(0, "mavlink already running");
thread_should_exit = false;
mavlink_task = task_spawn_cmd("mavlink",
@@ -793,15 +776,25 @@ int mavlink_main(int argc, char *argv[])
2048,
mavlink_thread_main,
(const char **)argv);
+
+ while (!thread_running) {
+ usleep(200);
+ }
+
exit(0);
}
if (!strcmp(argv[1], "stop")) {
+
+ /* this is not an error */
+ if (!thread_running)
+ errx(0, "mavlink already stopped");
+
thread_should_exit = true;
while (thread_running) {
usleep(200000);
- printf(".");
+ warnx(".");
}
warnx("terminated.");
diff --git a/src/modules/mavlink/mavlink_bridge_header.h b/src/modules/mavlink/mavlink_bridge_header.h
index 0010bb341..149efda60 100644
--- a/src/modules/mavlink/mavlink_bridge_header.h
+++ b/src/modules/mavlink/mavlink_bridge_header.h
@@ -73,9 +73,11 @@ extern mavlink_system_t mavlink_system;
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
* @param ch Character to send
*/
-extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, int length);
+extern void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length);
-mavlink_status_t *mavlink_get_channel_status(uint8_t chan);
-mavlink_message_t *mavlink_get_channel_buffer(uint8_t chan);
+extern mavlink_status_t *mavlink_get_channel_status(uint8_t chan);
+extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t chan);
+
+#include <v1.0/common/mavlink.h>
#endif /* MAVLINK_BRIDGE_HEADER_H */
diff --git a/src/modules/mavlink/mavlink_hil.h b/src/modules/mavlink/mavlink_hil.h
index 8c7a5b514..744ed7d94 100644
--- a/src/modules/mavlink/mavlink_hil.h
+++ b/src/modules/mavlink/mavlink_hil.h
@@ -41,15 +41,6 @@
extern bool mavlink_hil_enabled;
-extern struct vehicle_global_position_s hil_global_pos;
-extern struct vehicle_attitude_s hil_attitude;
-extern struct sensor_combined_s hil_sensors;
-extern struct vehicle_gps_position_s hil_gps;
-extern orb_advert_t pub_hil_global_pos;
-extern orb_advert_t pub_hil_attitude;
-extern orb_advert_t pub_hil_sensors;
-extern orb_advert_t pub_hil_gps;
-
/**
* Enable / disable Hardware in the Loop simulation mode.
*
diff --git a/src/modules/mavlink/mavlink_parameters.c b/src/modules/mavlink/mavlink_parameters.c
index 819f3441b..18ca7a854 100644
--- a/src/modules/mavlink/mavlink_parameters.c
+++ b/src/modules/mavlink/mavlink_parameters.c
@@ -40,7 +40,6 @@
*/
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include "mavlink_parameters.h"
#include <uORB/uORB.h>
#include "math.h" /* isinf / isnan checks */
diff --git a/src/modules/mavlink/mavlink_receiver.c b/src/modules/mavlink/mavlink_receiver.cpp
index 940d030b2..7b6fad658 100644
--- a/src/modules/mavlink/mavlink_receiver.c
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -49,9 +49,11 @@
#include <fcntl.h>
#include <mqueue.h>
#include <string.h>
-#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_gyro.h>
+#include <drivers/drv_mag.h>
+#include <drivers/drv_baro.h>
#include <time.h>
#include <float.h>
#include <unistd.h>
@@ -62,10 +64,19 @@
#include <stdlib.h>
#include <poll.h>
+#include <mathlib/mathlib.h>
+
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <systemlib/airspeed.h>
#include <mavlink/mavlink_log.h>
+#include <commander/px4_custom_mode.h>
+#include <geo/geo.h>
+
+__BEGIN_DECLS
+#include "mavlink_bridge_header.h"
#include "waypoints.h"
#include "orb_topics.h"
#include "missionlib.h"
@@ -73,8 +84,12 @@
#include "mavlink_parameters.h"
#include "util.h"
+extern bool gcs_link;
+
+__END_DECLS
+
/* XXX should be in a header somewhere */
-pthread_t receive_start(int uart);
+extern "C" pthread_t receive_start(int uart);
static void handle_message(mavlink_message_t *msg);
static void *receive_thread(void *arg);
@@ -85,21 +100,39 @@ static struct vehicle_command_s vcmd;
static struct offboard_control_setpoint_s offboard_control_sp;
struct vehicle_global_position_s hil_global_pos;
+struct vehicle_local_position_s hil_local_pos;
struct vehicle_attitude_s hil_attitude;
struct vehicle_gps_position_s hil_gps;
struct sensor_combined_s hil_sensors;
-orb_advert_t pub_hil_global_pos = -1;
-orb_advert_t pub_hil_attitude = -1;
-orb_advert_t pub_hil_gps = -1;
-orb_advert_t pub_hil_sensors = -1;
+struct battery_status_s hil_battery_status;
+static orb_advert_t pub_hil_global_pos = -1;
+static orb_advert_t pub_hil_local_pos = -1;
+static orb_advert_t pub_hil_attitude = -1;
+static orb_advert_t pub_hil_gps = -1;
+static orb_advert_t pub_hil_sensors = -1;
+static orb_advert_t pub_hil_gyro = -1;
+static orb_advert_t pub_hil_accel = -1;
+static orb_advert_t pub_hil_mag = -1;
+static orb_advert_t pub_hil_baro = -1;
+static orb_advert_t pub_hil_airspeed = -1;
+static orb_advert_t pub_hil_battery = -1;
+
+/* packet counter */
+static int hil_counter = 0;
+static int hil_frames = 0;
+static uint64_t old_timestamp = 0;
static orb_advert_t cmd_pub = -1;
static orb_advert_t flow_pub = -1;
static orb_advert_t offboard_control_sp_pub = -1;
static orb_advert_t vicon_position_pub = -1;
+static orb_advert_t telemetry_status_pub = -1;
-extern bool gcs_link;
+// variables for HIL reference position
+static int32_t lat0 = 0;
+static int32_t lon0 = 0;
+static double alt0 = 0;
static void
handle_message(mavlink_message_t *msg)
@@ -131,7 +164,8 @@ handle_message(mavlink_message_t *msg)
vcmd.param5 = cmd_mavlink.param5;
vcmd.param6 = cmd_mavlink.param6;
vcmd.param7 = cmd_mavlink.param7;
- vcmd.command = cmd_mavlink.command;
+ // 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;
@@ -141,10 +175,11 @@ handle_message(mavlink_message_t *msg)
/* check if topic is advertised */
if (cmd_pub <= 0) {
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
- }
- /* publish */
- orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
+ } else {
+ /* publish */
+ orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
+ }
}
}
}
@@ -179,15 +214,17 @@ handle_message(mavlink_message_t *msg)
mavlink_set_mode_t new_mode;
mavlink_msg_set_mode_decode(msg, &new_mode);
+ union px4_custom_mode custom_mode;
+ custom_mode.data = new_mode.custom_mode;
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
vcmd.param1 = new_mode.base_mode;
- vcmd.param2 = new_mode.custom_mode;
+ vcmd.param2 = custom_mode.main_mode;
vcmd.param3 = 0;
vcmd.param4 = 0;
vcmd.param5 = 0;
vcmd.param6 = 0;
vcmd.param7 = 0;
- vcmd.command = MAV_CMD_DO_SET_MODE;
+ vcmd.command = VEHICLE_CMD_DO_SET_MODE;
vcmd.target_system = new_mode.target_system;
vcmd.target_component = MAV_COMP_ID_ALL;
vcmd.source_system = msg->sysid;
@@ -281,7 +318,7 @@ handle_message(mavlink_message_t *msg)
}
offboard_control_sp.armed = ml_armed;
- offboard_control_sp.mode = ml_mode;
+ offboard_control_sp.mode = static_cast<enum OFFBOARD_CONTROL_MODE>(ml_mode);
offboard_control_sp.timestamp = hrt_absolute_time();
@@ -296,6 +333,33 @@ handle_message(mavlink_message_t *msg)
}
}
+ /* handle status updates of the radio */
+ if (msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
+
+ struct telemetry_status_s tstatus;
+
+ mavlink_radio_status_t rstatus;
+ mavlink_msg_radio_status_decode(msg, &rstatus);
+
+ /* publish telemetry status topic */
+ tstatus.timestamp = hrt_absolute_time();
+ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
+ tstatus.rssi = rstatus.rssi;
+ tstatus.remote_rssi = rstatus.remrssi;
+ tstatus.txbuf = rstatus.txbuf;
+ tstatus.noise = rstatus.noise;
+ tstatus.remote_noise = rstatus.remnoise;
+ tstatus.rxerrors = rstatus.rxerrors;
+ tstatus.fixed = rstatus.fixed;
+
+ if (telemetry_status_pub == 0) {
+ telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus);
+
+ } else {
+ orb_publish(ORB_ID(telemetry_status), telemetry_status_pub, &tstatus);
+ }
+ }
+
/*
* Only decode hil messages in HIL mode.
*
@@ -308,31 +372,25 @@ handle_message(mavlink_message_t *msg)
uint64_t timestamp = hrt_absolute_time();
- if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) {
+ if (msg->msgid == MAVLINK_MSG_ID_HIL_SENSOR) {
- mavlink_highres_imu_t imu;
- mavlink_msg_highres_imu_decode(msg, &imu);
-
- /* packet counter */
- static uint16_t hil_counter = 0;
- static uint16_t hil_frames = 0;
- static uint64_t old_timestamp = 0;
+ mavlink_hil_sensor_t imu;
+ mavlink_msg_hil_sensor_decode(msg, &imu);
/* sensors general */
hil_sensors.timestamp = hrt_absolute_time();
/* hil gyro */
static const float mrad2rad = 1.0e-3f;
- hil_sensors.gyro_counter = hil_counter;
hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad;
hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad;
hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad;
hil_sensors.gyro_rad_s[0] = imu.xgyro;
hil_sensors.gyro_rad_s[1] = imu.ygyro;
hil_sensors.gyro_rad_s[2] = imu.zgyro;
+ hil_sensors.gyro_counter = hil_counter;
/* accelerometer */
- hil_sensors.accelerometer_counter = hil_counter;
static const float mg2ms2 = 9.8f / 1000.0f;
hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
@@ -342,15 +400,15 @@ handle_message(mavlink_message_t *msg)
hil_sensors.accelerometer_m_s2[2] = imu.zacc;
hil_sensors.accelerometer_mode = 0; // TODO what is this?
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
+ hil_sensors.accelerometer_counter = hil_counter;
/* adc */
- hil_sensors.adc_voltage_v[0] = 0;
- hil_sensors.adc_voltage_v[1] = 0;
- hil_sensors.adc_voltage_v[2] = 0;
+ hil_sensors.adc_voltage_v[0] = 0.0f;
+ hil_sensors.adc_voltage_v[1] = 0.0f;
+ hil_sensors.adc_voltage_v[2] = 0.0f;
/* magnetometer */
float mga2ga = 1.0e-3f;
- hil_sensors.magnetometer_counter = hil_counter;
hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga;
hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga;
hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga;
@@ -360,18 +418,141 @@ handle_message(mavlink_message_t *msg)
hil_sensors.magnetometer_range_ga = 32.7f; // int16
hil_sensors.magnetometer_mode = 0; // TODO what is this
hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;
+ hil_sensors.magnetometer_counter = hil_counter;
/* baro */
hil_sensors.baro_pres_mbar = imu.abs_pressure;
hil_sensors.baro_alt_meter = imu.pressure_alt;
hil_sensors.baro_temp_celcius = imu.temperature;
+ hil_sensors.baro_counter = hil_counter;
- hil_sensors.gyro_counter = hil_counter;
- hil_sensors.magnetometer_counter = hil_counter;
- hil_sensors.accelerometer_counter = hil_counter;
+ /* differential pressure */
+ hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
+ hil_sensors.differential_pressure_counter = hil_counter;
- /* publish */
- orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);
+ /* airspeed from differential pressure, ambient pressure and temp */
+ struct airspeed_s airspeed;
+
+ float ias = calc_indicated_airspeed(hil_sensors.differential_pressure_pa);
+ // XXX need to fix this
+ float tas = ias;
+
+ airspeed.timestamp = hrt_absolute_time();
+ airspeed.indicated_airspeed_m_s = ias;
+ airspeed.true_airspeed_m_s = tas;
+
+ if (pub_hil_airspeed < 0) {
+ pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);
+
+ } else {
+ orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
+ }
+
+ //warnx("SENSOR: IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);
+
+ /* individual sensor publications */
+ struct gyro_report gyro;
+ gyro.x_raw = imu.xgyro / mrad2rad;
+ gyro.y_raw = imu.ygyro / mrad2rad;
+ gyro.z_raw = imu.zgyro / mrad2rad;
+ gyro.x = imu.xgyro;
+ gyro.y = imu.ygyro;
+ gyro.z = imu.zgyro;
+ gyro.temperature = imu.temperature;
+ gyro.timestamp = hrt_absolute_time();
+
+ if (pub_hil_gyro < 0) {
+ pub_hil_gyro = orb_advertise(ORB_ID(sensor_gyro), &gyro);
+
+ } else {
+ orb_publish(ORB_ID(sensor_gyro), pub_hil_gyro, &gyro);
+ }
+
+ struct accel_report accel;
+
+ accel.x_raw = imu.xacc / mg2ms2;
+
+ accel.y_raw = imu.yacc / mg2ms2;
+
+ accel.z_raw = imu.zacc / mg2ms2;
+
+ accel.x = imu.xacc;
+
+ accel.y = imu.yacc;
+
+ accel.z = imu.zacc;
+
+ accel.temperature = imu.temperature;
+
+ accel.timestamp = hrt_absolute_time();
+
+ if (pub_hil_accel < 0) {
+ pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);
+
+ } else {
+ orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
+ }
+
+ struct mag_report mag;
+
+ mag.x_raw = imu.xmag / mga2ga;
+
+ mag.y_raw = imu.ymag / mga2ga;
+
+ mag.z_raw = imu.zmag / mga2ga;
+
+ mag.x = imu.xmag;
+
+ mag.y = imu.ymag;
+
+ mag.z = imu.zmag;
+
+ mag.timestamp = hrt_absolute_time();
+
+ if (pub_hil_mag < 0) {
+ pub_hil_mag = orb_advertise(ORB_ID(sensor_mag), &mag);
+
+ } else {
+ orb_publish(ORB_ID(sensor_mag), pub_hil_mag, &mag);
+ }
+
+ struct baro_report baro;
+
+ baro.pressure = imu.abs_pressure;
+
+ baro.altitude = imu.pressure_alt;
+
+ baro.temperature = imu.temperature;
+
+ baro.timestamp = hrt_absolute_time();
+
+ if (pub_hil_baro < 0) {
+ pub_hil_baro = orb_advertise(ORB_ID(sensor_baro), &baro);
+
+ } else {
+ orb_publish(ORB_ID(sensor_baro), pub_hil_baro, &baro);
+ }
+
+ /* publish combined sensor topic */
+ if (pub_hil_sensors > 0) {
+ orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);
+
+ } else {
+ pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
+ }
+
+ /* fill in HIL battery status */
+ hil_battery_status.timestamp = hrt_absolute_time();
+ hil_battery_status.voltage_v = 11.1f;
+ hil_battery_status.current_a = 10.0f;
+
+ /* lazily publish the battery voltage */
+ if (pub_hil_battery > 0) {
+ orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);
+
+ } else {
+ pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
+ }
// increment counters
hil_counter++;
@@ -379,21 +560,16 @@ handle_message(mavlink_message_t *msg)
// output
if ((timestamp - old_timestamp) > 10000000) {
- printf("receiving hil imu at %d hz\n", hil_frames/10);
+ printf("receiving hil sensor at %d hz\n", hil_frames / 10);
old_timestamp = timestamp;
hil_frames = 0;
}
}
- if (msg->msgid == MAVLINK_MSG_ID_GPS_RAW_INT) {
-
- mavlink_gps_raw_int_t gps;
- mavlink_msg_gps_raw_int_decode(msg, &gps);
+ if (msg->msgid == MAVLINK_MSG_ID_HIL_GPS) {
- /* packet counter */
- static uint16_t hil_counter = 0;
- static uint16_t hil_frames = 0;
- static uint64_t old_timestamp = 0;
+ mavlink_hil_gps_t gps;
+ mavlink_msg_hil_gps_decode(msg, &gps);
/* gps */
hil_gps.timestamp_position = gps.time_usec;
@@ -409,80 +585,174 @@ handle_message(mavlink_message_t *msg)
/* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */
float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f;
+
/* go back to -PI..PI */
if (heading_rad > M_PI_F)
heading_rad -= 2.0f * M_PI_F;
- hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(heading_rad);
- hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(heading_rad);
- hil_gps.vel_d_m_s = 0.0f;
+
+ hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m
+ hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m
+ hil_gps.vel_d_m_s = gps.vd * 1e-2f; // from cm to m
hil_gps.vel_ned_valid = true;
- /* COG (course over ground) is speced as -PI..+PI */
+ /* COG (course over ground) is spec'ed as -PI..+PI */
hil_gps.cog_rad = heading_rad;
hil_gps.fix_type = gps.fix_type;
hil_gps.satellites_visible = gps.satellites_visible;
- /* publish */
- orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);
+ /* publish GPS measurement data */
+ if (pub_hil_gps > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);
- // increment counters
- hil_counter += 1 ;
- hil_frames += 1 ;
+ } else {
+ pub_hil_gps = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
+ }
- // output
- // if ((timestamp - old_timestamp) > 10000000) {
- // printf("receiving hil gps at %d hz\n", hil_frames/10);
- // old_timestamp = timestamp;
- // hil_frames = 0;
- // }
}
- if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) {
-
- mavlink_hil_state_t hil_state;
- mavlink_msg_hil_state_decode(msg, &hil_state);
+ if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE_QUATERNION) {
- /* Calculate Rotation Matrix */
- //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode
-
- if (mavlink_system.type == MAV_TYPE_FIXED_WING) {
- //TODO: assuming low pitch and roll values for now
- hil_attitude.R[0][0] = cosf(hil_state.yaw);
- hil_attitude.R[0][1] = sinf(hil_state.yaw);
- hil_attitude.R[0][2] = 0.0f;
+ mavlink_hil_state_quaternion_t hil_state;
+ mavlink_msg_hil_state_quaternion_decode(msg, &hil_state);
- hil_attitude.R[1][0] = -sinf(hil_state.yaw);
- hil_attitude.R[1][1] = cosf(hil_state.yaw);
- hil_attitude.R[1][2] = 0.0f;
+ struct airspeed_s airspeed;
+ airspeed.timestamp = hrt_absolute_time();
+ airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f;
+ airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f;
- hil_attitude.R[2][0] = 0.0f;
- hil_attitude.R[2][1] = 0.0f;
- hil_attitude.R[2][2] = 1.0f;
+ if (pub_hil_airspeed < 0) {
+ pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);
- hil_attitude.R_valid = true;
+ } else {
+ orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
}
- hil_global_pos.lat = hil_state.lat;
- hil_global_pos.lon = hil_state.lon;
- hil_global_pos.alt = hil_state.alt / 1000.0f;
- hil_global_pos.vx = hil_state.vx / 100.0f;
- hil_global_pos.vy = hil_state.vy / 100.0f;
- hil_global_pos.vz = hil_state.vz / 100.0f;
+ uint64_t timestamp = hrt_absolute_time();
+
+ // publish global position
+ if (pub_hil_global_pos > 0) {
+ orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
+ // global position packet
+ hil_global_pos.timestamp = timestamp;
+ hil_global_pos.valid = true;
+ hil_global_pos.lat = hil_state.lat;
+ hil_global_pos.lon = hil_state.lon;
+ hil_global_pos.alt = hil_state.alt / 1000.0f;
+ hil_global_pos.vx = hil_state.vx / 100.0f;
+ hil_global_pos.vy = hil_state.vy / 100.0f;
+ hil_global_pos.vz = hil_state.vz / 100.0f;
+ } else {
+ pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
+ }
- /* set timestamp and notify processes (broadcast) */
- hil_global_pos.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
+ // publish local position
+ if (pub_hil_local_pos > 0) {
+ float x;
+ float y;
+ bool landed = hil_state.alt/1000.0f < (alt0 + 0.1); // XXX improve?
+ double lat = hil_state.lat*1e-7;
+ double lon = hil_state.lon*1e-7;
+ map_projection_project(lat, lon, &x, &y);
+ hil_local_pos.timestamp = timestamp;
+ hil_local_pos.xy_valid = true;
+ hil_local_pos.z_valid = true;
+ hil_local_pos.v_xy_valid = true;
+ hil_local_pos.v_z_valid = true;
+ hil_local_pos.x = x;
+ hil_local_pos.y = y;
+ hil_local_pos.z = alt0 - hil_state.alt/1000.0f;
+ hil_local_pos.vx = hil_state.vx/100.0f;
+ hil_local_pos.vy = hil_state.vy/100.0f;
+ hil_local_pos.vz = hil_state.vz/100.0f;
+ hil_local_pos.yaw = hil_attitude.yaw;
+ hil_local_pos.xy_global = true;
+ hil_local_pos.z_global = true;
+ hil_local_pos.ref_timestamp = timestamp;
+ hil_local_pos.ref_lat = hil_state.lat;
+ hil_local_pos.ref_lon = hil_state.lon;
+ hil_local_pos.ref_alt = alt0;
+ hil_local_pos.landed = landed;
+ orb_publish(ORB_ID(vehicle_local_position), pub_hil_local_pos, &hil_local_pos);
+ } else {
+ pub_hil_local_pos = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos);
+ lat0 = hil_state.lat;
+ lon0 = hil_state.lon;
+ alt0 = hil_state.alt / 1000.0f;
+ map_projection_init(hil_state.lat, hil_state.lon);
+ }
- hil_attitude.roll = hil_state.roll;
- hil_attitude.pitch = hil_state.pitch;
- hil_attitude.yaw = hil_state.yaw;
+ /* Calculate Rotation Matrix */
+ math::Quaternion q(hil_state.attitude_quaternion);
+ math::Dcm C_nb(q);
+ math::EulerAngles euler(C_nb);
+
+ /* set rotation matrix */
+ for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
+ hil_attitude.R[i][j] = C_nb(i, j);
+
+ hil_attitude.R_valid = true;
+
+ /* set quaternion */
+ hil_attitude.q[0] = q(0);
+ hil_attitude.q[1] = q(1);
+ hil_attitude.q[2] = q(2);
+ hil_attitude.q[3] = q(3);
+ hil_attitude.q_valid = true;
+
+ hil_attitude.roll = euler.getPhi();
+ hil_attitude.pitch = euler.getTheta();
+ hil_attitude.yaw = euler.getPsi();
hil_attitude.rollspeed = hil_state.rollspeed;
hil_attitude.pitchspeed = hil_state.pitchspeed;
hil_attitude.yawspeed = hil_state.yawspeed;
/* set timestamp and notify processes (broadcast) */
hil_attitude.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);
+
+ if (pub_hil_attitude > 0) {
+ orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);
+
+ } else {
+ pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
+ }
+
+ struct accel_report accel;
+
+ accel.x_raw = hil_state.xacc / 9.81f * 1e3f;
+
+ accel.y_raw = hil_state.yacc / 9.81f * 1e3f;
+
+ accel.z_raw = hil_state.zacc / 9.81f * 1e3f;
+
+ accel.x = hil_state.xacc;
+
+ accel.y = hil_state.yacc;
+
+ accel.z = hil_state.zacc;
+
+ accel.temperature = 25.0f;
+
+ accel.timestamp = hrt_absolute_time();
+
+ if (pub_hil_accel < 0) {
+ pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);
+
+ } else {
+ orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
+ }
+
+ /* fill in HIL battery status */
+ hil_battery_status.timestamp = hrt_absolute_time();
+ hil_battery_status.voltage_v = 11.1f;
+ hil_battery_status.current_a = 10.0f;
+
+ /* lazily publish the battery voltage */
+ if (pub_hil_battery > 0) {
+ orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);
+
+ } else {
+ pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
+ }
}
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
@@ -549,15 +819,23 @@ receive_thread(void *arg)
mavlink_message_t msg;
- prctl(PR_SET_NAME, "mavlink uart rcv", getpid());
+ prctl(PR_SET_NAME, "mavlink_uart_rcv", getpid());
- while (!thread_should_exit) {
+ struct pollfd fds[1];
+ fds[0].fd = uart_fd;
+ fds[0].events = POLLIN;
- struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
+ ssize_t nread = 0;
+ while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
+ if (nread < sizeof(buf)) {
+ /* to avoid reading very small chunks wait for data before reading */
+ usleep(1000);
+ }
+
/* non-blocking read. read may return negative values */
- ssize_t nread = read(uart_fd, buf, sizeof(buf));
+ nread = read(uart_fd, buf, sizeof(buf));
/* if read failed, this loop won't execute */
for (ssize_t i = 0; i < nread; i++) {
@@ -565,10 +843,10 @@ receive_thread(void *arg)
/* handle generic messages and commands */
handle_message(&msg);
- /* Handle packet with waypoint component */
+ /* handle packet with waypoint component */
mavlink_wpm_message_handler(&msg, &global_pos, &local_pos);
- /* Handle packet with parameter component */
+ /* handle packet with parameter component */
mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
}
}
@@ -589,12 +867,15 @@ receive_start(int uart)
fcntl(uart, F_SETFL, flags | O_NONBLOCK);
struct sched_param param;
+ (void)pthread_attr_getschedparam(&receiveloop_attr, &param);
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 2048);
+ pthread_attr_setstacksize(&receiveloop_attr, 3000);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
+
+ pthread_attr_destroy(&receiveloop_attr);
return thread;
}
diff --git a/src/modules/mavlink/missionlib.c b/src/modules/mavlink/missionlib.c
index d369e05ff..124b3b2ae 100644
--- a/src/modules/mavlink/missionlib.c
+++ b/src/modules/mavlink/missionlib.c
@@ -48,7 +48,6 @@
#include <mqueue.h>
#include <string.h>
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
#include <time.h>
#include <float.h>
@@ -60,10 +59,12 @@
#include <stdlib.h>
#include <poll.h>
+#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#include <mavlink/mavlink_log.h>
+#include "geo/geo.h"
#include "waypoints.h"
#include "orb_topics.h"
#include "missionlib.h"
@@ -73,6 +74,10 @@
#include "mavlink_parameters.h"
static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
+static uint64_t loiter_start_time;
+
+static bool set_special_fields(float param1, float param2, float param3, float param4, uint16_t command,
+ struct vehicle_global_position_setpoint_s *sp);
int
mavlink_missionlib_send_message(mavlink_message_t *msg)
@@ -123,6 +128,74 @@ uint64_t mavlink_missionlib_get_system_timestamp()
}
/**
+ * Set special vehicle setpoint fields based on current mission item.
+ *
+ * @return true if the mission item could be interpreted
+ * successfully, it return false on failure.
+ */
+bool set_special_fields(float param1, float param2, float param3, float param4, uint16_t command,
+ struct vehicle_global_position_setpoint_s *sp)
+{
+ switch (command) {
+ case MAV_CMD_NAV_LOITER_UNLIM:
+ sp->nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+ break;
+ case MAV_CMD_NAV_LOITER_TIME:
+ sp->nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ loiter_start_time = hrt_absolute_time();
+ break;
+ // case MAV_CMD_NAV_LOITER_TURNS:
+ // sp->nav_cmd = NAV_CMD_LOITER_TURN_COUNT;
+ // break;
+ case MAV_CMD_NAV_WAYPOINT:
+ sp->nav_cmd = NAV_CMD_WAYPOINT;
+ break;
+ case MAV_CMD_NAV_RETURN_TO_LAUNCH:
+ sp->nav_cmd = NAV_CMD_RETURN_TO_LAUNCH;
+ break;
+ case MAV_CMD_NAV_LAND:
+ sp->nav_cmd = NAV_CMD_LAND;
+ break;
+ case MAV_CMD_NAV_TAKEOFF:
+ sp->nav_cmd = NAV_CMD_TAKEOFF;
+ break;
+ default:
+ /* abort */
+ return false;
+ }
+
+ sp->loiter_radius = param3;
+ sp->loiter_direction = (param3 >= 0) ? 1 : -1;
+
+ sp->param1 = param1;
+ sp->param2 = param2;
+ sp->param3 = param3;
+ sp->param4 = param4;
+
+
+ /* define the turn distance */
+ float orbit = 15.0f;
+
+ if (command == (int)MAV_CMD_NAV_WAYPOINT) {
+
+ orbit = param2;
+
+ } else if (command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ command == (int)MAV_CMD_NAV_LOITER_UNLIM) {
+
+ orbit = param3;
+ } else {
+
+ // XXX set default orbit via param
+ // 15 initialized above
+ }
+
+ sp->turn_distance_xy = orbit;
+ sp->turn_distance_z = orbit;
+}
+
+/**
* This callback is executed each time a waypoint changes.
*
* It publishes the vehicle_global_position_setpoint_s or the
@@ -133,9 +206,13 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command)
{
static orb_advert_t global_position_setpoint_pub = -1;
+ static orb_advert_t global_position_set_triplet_pub = -1;
static orb_advert_t local_position_setpoint_pub = -1;
+ static unsigned last_waypoint_index = -1;
char buf[50] = {0};
+ // XXX include check if WP is supported, jump to next if not
+
/* Update controller setpoints */
if (frame == (int)MAV_FRAME_GLOBAL) {
/* global, absolute waypoint */
@@ -144,9 +221,10 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
sp.lon = param6_lon_y * 1e7f;
sp.altitude = param7_alt_z;
sp.altitude_is_relative = false;
- sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
+ sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
+ set_special_fields(param1, param2, param3, param4, command, &sp);
- /* Initialize publication if necessary */
+ /* Initialize setpoint publication if necessary */
if (global_position_setpoint_pub < 0) {
global_position_setpoint_pub = orb_advertise(ORB_ID(vehicle_global_position_setpoint), &sp);
@@ -154,6 +232,108 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp);
}
+
+ /* fill triplet: previous, current, next waypoint */
+ struct vehicle_global_position_set_triplet_s triplet;
+
+ /* current waypoint is same as sp */
+ memcpy(&(triplet.current), &sp, sizeof(sp));
+
+ /*
+ * Check if previous WP (in mission, not in execution order)
+ * is available and identify correct index
+ */
+ int last_setpoint_index = -1;
+ bool last_setpoint_valid = false;
+
+ if (index > 0) {
+ last_setpoint_index = index - 1;
+ }
+
+ while (last_setpoint_index >= 0) {
+
+ if (wpm->waypoints[last_setpoint_index].frame == (int)MAV_FRAME_GLOBAL &&
+ (wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT ||
+ wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ wpm->waypoints[last_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_UNLIM)) {
+ last_setpoint_valid = true;
+ break;
+ }
+
+ last_setpoint_index--;
+ }
+
+ /*
+ * Check if next WP (in mission, not in execution order)
+ * is available and identify correct index
+ */
+ int next_setpoint_index = -1;
+ bool next_setpoint_valid = false;
+
+ /* next waypoint */
+ if (wpm->size > 1) {
+ next_setpoint_index = index + 1;
+ }
+
+ while (next_setpoint_index < wpm->size) {
+
+ if (wpm->waypoints[next_setpoint_index].frame == (int)MAV_FRAME_GLOBAL && (wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_WAYPOINT ||
+ wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ wpm->waypoints[next_setpoint_index].command == (int)MAV_CMD_NAV_LOITER_UNLIM)) {
+ next_setpoint_valid = true;
+ break;
+ }
+
+ next_setpoint_index++;
+ }
+
+ /* populate last and next */
+
+ triplet.previous_valid = false;
+ triplet.next_valid = false;
+
+ if (last_setpoint_valid) {
+ triplet.previous_valid = true;
+ struct vehicle_global_position_setpoint_s sp;
+ sp.lat = wpm->waypoints[last_setpoint_index].x * 1e7f;
+ sp.lon = wpm->waypoints[last_setpoint_index].y * 1e7f;
+ sp.altitude = wpm->waypoints[last_setpoint_index].z;
+ sp.altitude_is_relative = false;
+ sp.yaw = _wrap_pi(wpm->waypoints[last_setpoint_index].param4 / 180.0f * M_PI_F);
+ set_special_fields(wpm->waypoints[last_setpoint_index].param1,
+ wpm->waypoints[last_setpoint_index].param2,
+ wpm->waypoints[last_setpoint_index].param3,
+ wpm->waypoints[last_setpoint_index].param4,
+ wpm->waypoints[last_setpoint_index].command, &sp);
+ memcpy(&(triplet.previous), &sp, sizeof(sp));
+ }
+
+ if (next_setpoint_valid) {
+ triplet.next_valid = true;
+ struct vehicle_global_position_setpoint_s sp;
+ sp.lat = wpm->waypoints[next_setpoint_index].x * 1e7f;
+ sp.lon = wpm->waypoints[next_setpoint_index].y * 1e7f;
+ sp.altitude = wpm->waypoints[next_setpoint_index].z;
+ sp.altitude_is_relative = false;
+ sp.yaw = _wrap_pi(wpm->waypoints[next_setpoint_index].param4 / 180.0f * M_PI_F);
+ set_special_fields(wpm->waypoints[next_setpoint_index].param1,
+ wpm->waypoints[next_setpoint_index].param2,
+ wpm->waypoints[next_setpoint_index].param3,
+ wpm->waypoints[next_setpoint_index].param4,
+ wpm->waypoints[next_setpoint_index].command, &sp);
+ memcpy(&(triplet.next), &sp, sizeof(sp));
+ }
+
+ /* Initialize triplet publication if necessary */
+ if (global_position_set_triplet_pub < 0) {
+ global_position_set_triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &triplet);
+
+ } else {
+ orb_publish(ORB_ID(vehicle_global_position_set_triplet), global_position_set_triplet_pub, &triplet);
+ }
+
sprintf(buf, "[mp] WP#%i lat: % 3.6f/lon % 3.6f/alt % 4.6f/hdg %3.4f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
} else if (frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
@@ -163,7 +343,8 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
sp.lon = param6_lon_y * 1e7f;
sp.altitude = param7_alt_z;
sp.altitude_is_relative = true;
- sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
+ sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
+ set_special_fields(param1, param2, param3, param4, command, &sp);
/* Initialize publication if necessary */
if (global_position_setpoint_pub < 0) {
@@ -173,6 +354,8 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
orb_publish(ORB_ID(vehicle_global_position_setpoint), global_position_setpoint_pub, &sp);
}
+
+
sprintf(buf, "[mp] WP#%i (lat: %f/lon %f/rel alt %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
} else if (frame == (int)MAV_FRAME_LOCAL_ENU || frame == (int)MAV_FRAME_LOCAL_NED) {
@@ -181,7 +364,7 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
sp.x = param5_lat_x;
sp.y = param6_lon_y;
sp.z = param7_alt_z;
- sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
+ sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
/* Initialize publication if necessary */
if (local_position_setpoint_pub < 0) {
@@ -192,8 +375,15 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
}
sprintf(buf, "[mp] WP#%i (x: %f/y %f/z %f/hdg %f\n", (int)index, (double)param5_lat_x, (double)param6_lon_y, (double)param7_alt_z, (double)param4);
+ } else {
+ warnx("non-navigation WP, ignoring");
+ mavlink_missionlib_send_gcs_string("[mp] Unknown waypoint type, ignoring.");
+ return;
}
+ /* only set this for known waypoint types (non-navigation types would have returned earlier) */
+ last_waypoint_index = index;
+
mavlink_missionlib_send_gcs_string(buf);
printf("%s\n", buf);
//printf("[mavlink mp] new setpoint\n");//: frame: %d, lat: %d, lon: %d, alt: %d, yaw: %d\n", frame, param5_lat_x*1000, param6_lon_y*1000, param7_alt_z*1000, param4*1000);
diff --git a/src/modules/mavlink/missionlib.h b/src/modules/mavlink/missionlib.h
index c2ca735b3..c7d8f90c5 100644
--- a/src/modules/mavlink/missionlib.h
+++ b/src/modules/mavlink/missionlib.h
@@ -39,7 +39,7 @@
#pragma once
-#include <v1.0/common/mavlink.h>
+#include "mavlink_bridge_header.h"
//extern void mavlink_wpm_send_message(mavlink_message_t *msg);
//extern void mavlink_wpm_send_gcs_string(const char *string);
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index cbf08aeb2..5d3d6a73c 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -39,8 +39,7 @@ MODULE_COMMAND = mavlink
SRCS += mavlink.c \
missionlib.c \
mavlink_parameters.c \
- mavlink_log.c \
- mavlink_receiver.c \
+ mavlink_receiver.cpp \
orb_listener.c \
waypoints.c
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 295cd5e28..e1dabfd21 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -47,7 +47,6 @@
#include <fcntl.h>
#include <string.h>
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
#include <time.h>
#include <float.h>
@@ -55,6 +54,7 @@
#include <sys/prctl.h>
#include <stdlib.h>
#include <poll.h>
+#include <lib/geo/geo.h>
#include <mavlink/mavlink_log.h>
@@ -68,10 +68,14 @@ extern bool gcs_link;
struct vehicle_global_position_s global_pos;
struct vehicle_local_position_s local_pos;
+struct navigation_capabilities_s nav_cap;
struct vehicle_status_s v_status;
struct rc_channels_s rc;
struct rc_input_values rc_raw;
struct actuator_armed_s armed;
+struct actuator_controls_s actuators_0;
+struct vehicle_attitude_s att;
+struct airspeed_s airspeed;
struct mavlink_subscriptions mavlink_subs;
@@ -89,6 +93,8 @@ static unsigned int gps_counter;
*/
static uint64_t last_sensor_timestamp;
+static hrt_abstime last_sent_vfr = 0;
+
static void *uorb_receive_thread(void *arg);
struct listener {
@@ -97,6 +103,8 @@ struct listener {
uintptr_t arg;
};
+uint16_t cm_uint16_from_m_float(float m);
+
static void l_sensor_combined(const struct listener *l);
static void l_vehicle_attitude(const struct listener *l);
static void l_vehicle_gps_position(const struct listener *l);
@@ -116,6 +124,8 @@ static void l_debug_key_value(const struct listener *l);
static void l_optical_flow(const struct listener *l);
static void l_vehicle_rates_setpoint(const struct listener *l);
static void l_home(const struct listener *l);
+static void l_airspeed(const struct listener *l);
+static void l_nav_cap(const struct listener *l);
static const struct listener listeners[] = {
{l_sensor_combined, &mavlink_subs.sensor_sub, 0},
@@ -140,10 +150,25 @@ static const struct listener listeners[] = {
{l_optical_flow, &mavlink_subs.optical_flow, 0},
{l_vehicle_rates_setpoint, &mavlink_subs.rates_setpoint_sub, 0},
{l_home, &mavlink_subs.home_sub, 0},
+ {l_airspeed, &mavlink_subs.airspeed_sub, 0},
+ {l_nav_cap, &mavlink_subs.navigation_capabilities_sub, 0},
};
static const unsigned n_listeners = sizeof(listeners) / sizeof(listeners[0]);
+uint16_t
+cm_uint16_from_m_float(float m)
+{
+ if (m < 0.0f) {
+ return 0;
+
+ } else if (m > 655.35f) {
+ return 65535;
+ }
+
+ return (uint16_t)(m * 100.0f);
+}
+
void
l_sensor_combined(const struct listener *l)
{
@@ -192,7 +217,7 @@ l_sensor_combined(const struct listener *l)
raw.gyro_rad_s[1], raw.gyro_rad_s[2],
raw.magnetometer_ga[0],
raw.magnetometer_ga[1], raw.magnetometer_ga[2],
- raw.baro_pres_mbar, 0 /* no diff pressure yet */,
+ raw.baro_pres_mbar, raw.differential_pressure_pa,
raw.baro_alt_meter, raw.baro_temp_celcius,
fields_updated);
@@ -202,13 +227,10 @@ l_sensor_combined(const struct listener *l)
void
l_vehicle_attitude(const struct listener *l)
{
- struct vehicle_attitude_s att;
-
-
/* copy attitude data into local buffer */
orb_copy(ORB_ID(vehicle_attitude), mavlink_subs.att_sub, &att);
- if (gcs_link)
+ if (gcs_link) {
/* send sensor values */
mavlink_msg_attitude_send(MAVLINK_COMM_0,
last_sensor_timestamp / 1000,
@@ -218,6 +240,30 @@ l_vehicle_attitude(const struct listener *l)
att.rollspeed,
att.pitchspeed,
att.yawspeed);
+
+ /* limit VFR message rate to 10Hz */
+ hrt_abstime t = hrt_absolute_time();
+ if (t >= last_sent_vfr + 100000) {
+ last_sent_vfr = t;
+ float groundspeed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
+ uint16_t heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F;
+ float throttle = armed.armed ? actuators_0.control[3] * 100.0f : 0.0f;
+ mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, global_pos.alt, -global_pos.vz);
+ }
+
+ /* send quaternion values if it exists */
+ if(att.q_valid) {
+ mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
+ last_sensor_timestamp / 1000,
+ att.q[0],
+ att.q[1],
+ att.q[2],
+ att.q[3],
+ att.rollspeed,
+ att.pitchspeed,
+ att.yawspeed);
+ }
+ }
attitude_counter++;
}
@@ -231,11 +277,7 @@ l_vehicle_gps_position(const struct listener *l)
orb_copy(ORB_ID(vehicle_gps_position), mavlink_subs.gps_sub, &gps);
/* GPS COG is 0..2PI in degrees * 1e2 */
- float cog_deg = gps.cog_rad;
- if (cog_deg > M_PI_F)
- cog_deg -= 2.0f * M_PI_F;
- cog_deg *= M_RAD_TO_DEG_F;
-
+ float cog_deg = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F;
/* GPS position */
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
@@ -244,10 +286,10 @@ l_vehicle_gps_position(const struct listener *l)
gps.lat,
gps.lon,
gps.alt,
- gps.eph_m * 1e2f, // from m to cm
- gps.epv_m * 1e2f, // from m to cm
+ cm_uint16_from_m_float(gps.eph_m),
+ cm_uint16_from_m_float(gps.epv_m),
gps.vel_m_s * 1e2f, // from m/s to cm/s
- cog_deg * 1e2f, // from rad to deg * 100
+ cog_deg * 1e2f, // from deg to deg * 100
gps.satellites_visible);
/* update SAT info every 10 seconds */
@@ -272,19 +314,23 @@ l_vehicle_status(const struct listener *l)
orb_copy(ORB_ID(actuator_armed), mavlink_subs.armed_sub, &armed);
/* enable or disable HIL */
- set_hil_on_off(v_status.flag_hil_enabled);
+ if (v_status.hil_state == HIL_STATE_ON)
+ set_hil_on_off(true);
+ else if (v_status.hil_state == HIL_STATE_OFF)
+ set_hil_on_off(false);
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state = 0;
- uint8_t mavlink_mode = 0;
- get_mavlink_mode_and_state(&mavlink_state, &mavlink_mode);
+ uint8_t mavlink_base_mode = 0;
+ uint32_t mavlink_custom_mode = 0;
+ get_mavlink_mode_and_state(&mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
/* send heartbeat */
mavlink_msg_heartbeat_send(chan,
mavlink_system.type,
MAV_AUTOPILOT_PX4,
- mavlink_mode,
- v_status.state_machine,
+ mavlink_base_mode,
+ mavlink_custom_mode,
mavlink_state);
}
@@ -302,20 +348,26 @@ l_input_rc(const struct listener *l)
/* copy rc channels into local buffer */
orb_copy(ORB_ID(input_rc), mavlink_subs.input_rc_sub, &rc_raw);
- if (gcs_link)
- /* Channels are sent in MAVLink main loop at a fixed interval */
- mavlink_msg_rc_channels_raw_send(chan,
- rc_raw.timestamp / 1000,
- 0,
- (rc_raw.channel_count > 0) ? rc_raw.values[0] : UINT16_MAX,
- (rc_raw.channel_count > 1) ? rc_raw.values[1] : UINT16_MAX,
- (rc_raw.channel_count > 2) ? rc_raw.values[2] : UINT16_MAX,
- (rc_raw.channel_count > 3) ? rc_raw.values[3] : UINT16_MAX,
- (rc_raw.channel_count > 4) ? rc_raw.values[4] : UINT16_MAX,
- (rc_raw.channel_count > 5) ? rc_raw.values[5] : UINT16_MAX,
- (rc_raw.channel_count > 6) ? rc_raw.values[6] : UINT16_MAX,
- (rc_raw.channel_count > 7) ? rc_raw.values[7] : UINT16_MAX,
- 255);
+ if (gcs_link) {
+
+ const unsigned port_width = 8;
+
+ for (unsigned i = 0; (i * port_width) < rc_raw.channel_count; i++) {
+ /* Channels are sent in MAVLink main loop at a fixed interval */
+ mavlink_msg_rc_channels_raw_send(chan,
+ rc_raw.timestamp_publication / 1000,
+ i,
+ (rc_raw.channel_count > (i * port_width) + 0) ? rc_raw.values[(i * port_width) + 0] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 1) ? rc_raw.values[(i * port_width) + 1] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 2) ? rc_raw.values[(i * port_width) + 2] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 3) ? rc_raw.values[(i * port_width) + 3] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 4) ? rc_raw.values[(i * port_width) + 4] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 5) ? rc_raw.values[(i * port_width) + 5] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 6) ? rc_raw.values[(i * port_width) + 6] : UINT16_MAX,
+ (rc_raw.channel_count > (i * port_width) + 7) ? rc_raw.values[(i * port_width) + 7] : UINT16_MAX,
+ rc_raw.rssi);
+ }
+ }
}
void
@@ -324,28 +376,16 @@ l_global_position(const struct listener *l)
/* copy global position data into local buffer */
orb_copy(ORB_ID(vehicle_global_position), mavlink_subs.global_pos_sub, &global_pos);
- uint64_t timestamp = global_pos.timestamp;
- int32_t lat = global_pos.lat;
- int32_t lon = global_pos.lon;
- int32_t alt = (int32_t)(global_pos.alt * 1000);
- int32_t relative_alt = (int32_t)(global_pos.relative_alt * 1000.0f);
- int16_t vx = (int16_t)(global_pos.vx * 100.0f);
- int16_t vy = (int16_t)(global_pos.vy * 100.0f);
- int16_t vz = (int16_t)(global_pos.vz * 100.0f);
-
- /* heading in degrees * 10, from 0 to 36.000) */
- uint16_t hdg = (global_pos.hdg / M_PI_F) * (180.0f * 10.0f) + (180.0f * 10.0f);
-
mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
- timestamp / 1000,
- lat,
- lon,
- alt,
- relative_alt,
- vx,
- vy,
- vz,
- hdg);
+ global_pos.timestamp / 1000,
+ global_pos.lat,
+ global_pos.lon,
+ global_pos.alt * 1000.0f,
+ global_pos.relative_alt * 1000.0f,
+ global_pos.vx * 100.0f,
+ global_pos.vy * 100.0f,
+ global_pos.vz * 100.0f,
+ _wrap_2pi(global_pos.yaw) * M_RAD_TO_DEG_F * 100.0f);
}
void
@@ -383,8 +423,8 @@ l_global_position_setpoint(const struct listener *l)
coordinate_frame,
global_sp.lat,
global_sp.lon,
- global_sp.altitude,
- global_sp.yaw);
+ global_sp.altitude * 1000.0f,
+ global_sp.yaw * M_RAD_TO_DEG_F * 100.0f);
}
void
@@ -455,7 +495,8 @@ l_actuator_outputs(const struct listener *l)
if (gcs_link) {
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000,
- l->arg /* port number */,
+ l->arg /* port number - needs GCS support */,
+ /* QGC has port number support already */
act_outputs.output[0],
act_outputs.output[1],
act_outputs.output[2],
@@ -465,13 +506,14 @@ l_actuator_outputs(const struct listener *l)
act_outputs.output[6],
act_outputs.output[7]);
- /* only send in HIL mode */
- if (mavlink_hil_enabled && armed.armed) {
+ /* only send in HIL mode and only send first group for HIL */
+ if (mavlink_hil_enabled && armed.armed && ids[l->arg] == ORB_ID(actuator_outputs_0)) {
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state = 0;
- uint8_t mavlink_mode = 0;
- get_mavlink_mode_and_state(&mavlink_state, &mavlink_mode);
+ uint8_t mavlink_base_mode = 0;
+ uint32_t mavlink_custom_mode = 0;
+ get_mavlink_mode_and_state(&mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
/* HIL message as per MAVLink spec */
@@ -488,7 +530,7 @@ l_actuator_outputs(const struct listener *l)
-1,
-1,
-1,
- mavlink_mode,
+ mavlink_base_mode,
0);
} else if (mavlink_system.type == MAV_TYPE_HEXAROTOR) {
@@ -502,7 +544,7 @@ l_actuator_outputs(const struct listener *l)
((act_outputs.output[5] - 900.0f) / 600.0f) / 2.0f,
-1,
-1,
- mavlink_mode,
+ mavlink_base_mode,
0);
} else if (mavlink_system.type == MAV_TYPE_OCTOROTOR) {
@@ -516,7 +558,7 @@ l_actuator_outputs(const struct listener *l)
((act_outputs.output[5] - 900.0f) / 600.0f) / 2.0f,
((act_outputs.output[6] - 900.0f) / 600.0f) / 2.0f,
((act_outputs.output[7] - 900.0f) / 600.0f) / 2.0f,
- mavlink_mode,
+ mavlink_base_mode,
0);
} else {
@@ -530,7 +572,7 @@ l_actuator_outputs(const struct listener *l)
(act_outputs.output[5] - 1500.0f) / 500.0f,
(act_outputs.output[6] - 1500.0f) / 500.0f,
(act_outputs.output[7] - 1500.0f) / 500.0f,
- mavlink_mode,
+ mavlink_base_mode,
0);
}
}
@@ -564,28 +606,26 @@ l_manual_control_setpoint(const struct listener *l)
void
l_vehicle_attitude_controls(const struct listener *l)
{
- struct actuator_controls_effective_s actuators;
-
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, mavlink_subs.actuators_sub, &actuators);
+ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, mavlink_subs.actuators_sub, &actuators_0);
if (gcs_link) {
/* send, add spaces so that string buffer is at least 10 chars long */
mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
last_sensor_timestamp / 1000,
- "eff ctrl0 ",
- actuators.control_effective[0]);
+ "ctrl0 ",
+ actuators_0.control[0]);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
last_sensor_timestamp / 1000,
- "eff ctrl1 ",
- actuators.control_effective[1]);
+ "ctrl1 ",
+ actuators_0.control[1]);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
last_sensor_timestamp / 1000,
- "eff ctrl2 ",
- actuators.control_effective[2]);
+ "ctrl2 ",
+ actuators_0.control[2]);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
last_sensor_timestamp / 1000,
- "eff ctrl3 ",
- actuators.control_effective[3]);
+ "ctrl3 ",
+ actuators_0.control[3]);
}
}
@@ -626,11 +666,30 @@ l_home(const struct listener *l)
mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0, home.lat, home.lon, home.alt);
}
+void
+l_airspeed(const struct listener *l)
+{
+ orb_copy(ORB_ID(airspeed), mavlink_subs.airspeed_sub, &airspeed);
+}
+
+void
+l_nav_cap(const struct listener *l)
+{
+
+ orb_copy(ORB_ID(navigation_capabilities), mavlink_subs.navigation_capabilities_sub, &nav_cap);
+
+ mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
+ hrt_absolute_time() / 1000,
+ "turn dist",
+ nav_cap.turn_distance);
+
+}
+
static void *
uorb_receive_thread(void *arg)
{
/* Set thread name */
- prctl(PR_SET_NAME, "mavlink orb rcv", getpid());
+ prctl(PR_SET_NAME, "mavlink_orb_rcv", getpid());
/*
* set up poll to block for new data,
@@ -659,7 +718,7 @@ uorb_receive_thread(void *arg)
/* handle the poll result */
if (poll_ret == 0) {
- mavlink_missionlib_send_gcs_string("[mavlink] No telemetry data for 1 s");
+ /* silent */
} else if (poll_ret < 0) {
mavlink_missionlib_send_gcs_string("[mavlink] ERROR reading uORB data");
@@ -754,7 +813,7 @@ uorb_receive_start(void)
orb_set_interval(mavlink_subs.man_control_sp_sub, 100); /* 10Hz updates */
/* --- ACTUATOR CONTROL VALUE --- */
- mavlink_subs.actuators_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE);
+ mavlink_subs.actuators_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
orb_set_interval(mavlink_subs.actuators_sub, 100); /* 10Hz updates */
/* --- DEBUG VALUE OUTPUT --- */
@@ -765,6 +824,15 @@ uorb_receive_start(void)
mavlink_subs.optical_flow = orb_subscribe(ORB_ID(optical_flow));
orb_set_interval(mavlink_subs.optical_flow, 200); /* 5Hz updates */
+ /* --- AIRSPEED --- */
+ mavlink_subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ orb_set_interval(mavlink_subs.airspeed_sub, 200); /* 5Hz updates */
+
+ /* --- NAVIGATION CAPABILITIES --- */
+ mavlink_subs.navigation_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
+ orb_set_interval(mavlink_subs.navigation_capabilities_sub, 500); /* 2Hz updates */
+ nav_cap.turn_distance = 0.0f;
+
/* start the listener loop */
pthread_attr_t uorb_attr;
pthread_attr_init(&uorb_attr);
@@ -774,5 +842,7 @@ uorb_receive_start(void)
pthread_t thread;
pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL);
+
+ pthread_attr_destroy(&uorb_attr);
return thread;
}
diff --git a/src/modules/mavlink/orb_topics.h b/src/modules/mavlink/orb_topics.h
index d61cd43dc..91773843b 100644
--- a/src/modules/mavlink/orb_topics.h
+++ b/src/modules/mavlink/orb_topics.h
@@ -52,15 +52,22 @@
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/vehicle_global_position_set_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/debug_key_value.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/battery_status.h>
#include <drivers/drv_rc_input.h>
+#include <uORB/topics/navigation_capabilities.h>
struct mavlink_subscriptions {
int sensor_sub;
@@ -72,8 +79,10 @@ struct mavlink_subscriptions {
int act_3_sub;
int gps_sub;
int man_control_sp_sub;
- int armed_sub;
+ int safety_sub;
int actuators_sub;
+ int armed_sub;
+ int actuators_effective_sub;
int local_pos_sub;
int spa_sub;
int spl_sub;
@@ -83,6 +92,8 @@ struct mavlink_subscriptions {
int optical_flow;
int rates_setpoint_sub;
int home_sub;
+ int airspeed_sub;
+ int navigation_capabilities_sub;
};
extern struct mavlink_subscriptions mavlink_subs;
@@ -93,6 +104,9 @@ extern struct vehicle_global_position_s global_pos;
/** Local position */
extern struct vehicle_local_position_s local_pos;
+/** navigation capabilities */
+extern struct navigation_capabilities_s nav_cap;
+
/** Vehicle status */
extern struct vehicle_status_s v_status;
diff --git a/src/modules/mavlink/util.h b/src/modules/mavlink/util.h
index a4ff06a88..5e5ee8261 100644
--- a/src/modules/mavlink/util.h
+++ b/src/modules/mavlink/util.h
@@ -51,4 +51,4 @@ extern mavlink_wpm_storage *wpm;
/**
* Translate the custom state into standard mavlink modes and state.
*/
-extern void get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode);
+extern void get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index a131b143b..7e4a2688f 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -45,6 +45,7 @@
#include <unistd.h>
#include <stdio.h>
+#include "mavlink_bridge_header.h"
#include "missionlib.h"
#include "waypoints.h"
#include "util.h"
@@ -245,64 +246,19 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq)
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}
-//float mavlink_wpm_distance_to_segment(uint16_t seq, float x, float y, float z)
-//{
-// if (seq < wpm->size)
-// {
-// mavlink_mission_item_t *cur = waypoints->at(seq);
-//
-// const PxVector3 A(cur->x, cur->y, cur->z);
-// const PxVector3 C(x, y, z);
-//
-// // seq not the second last waypoint
-// if ((uint16_t)(seq+1) < wpm->size)
-// {
-// mavlink_mission_item_t *next = waypoints->at(seq+1);
-// const PxVector3 B(next->x, next->y, next->z);
-// const float r = (B-A).dot(C-A) / (B-A).lengthSquared();
-// if (r >= 0 && r <= 1)
-// {
-// const PxVector3 P(A + r*(B-A));
-// return (P-C).length();
-// }
-// else if (r < 0.f)
-// {
-// return (C-A).length();
-// }
-// else
-// {
-// return (C-B).length();
-// }
-// }
-// else
-// {
-// return (C-A).length();
-// }
-// }
-// else
-// {
-// // if (verbose) // printf("ERROR: index out of bounds\n");
-// }
-// return -1.f;
-//}
-
/*
* Calculate distance in global frame.
*
* The distance calculation is based on the WGS84 geoid (GPS)
*/
-float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float lon, float alt)
+float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float lon, float alt, float *dist_xy, float *dist_z)
{
- //TODO: implement for z once altidude contoller is implemented
- static uint16_t counter;
-
-// if(counter % 10 == 0) printf(" x = %.10f, y = %.10f\n", x, y);
if (seq < wpm->size) {
- mavlink_mission_item_t *cur = &(wpm->waypoints[seq]);
+ mavlink_mission_item_t *wp = &(wpm->waypoints[seq]);
- double current_x_rad = cur->x / 180.0 * M_PI;
- double current_y_rad = cur->y / 180.0 * M_PI;
+ double current_x_rad = wp->x / 180.0 * M_PI;
+ double current_y_rad = wp->y / 180.0 * M_PI;
double x_rad = lat / 180.0 * M_PI;
double y_rad = lon / 180.0 * M_PI;
@@ -314,20 +270,24 @@ float mavlink_wpm_distance_to_point_global_wgs84(uint16_t seq, float lat, float
const double radius_earth = 6371000.0;
- return radius_earth * c;
+ float dxy = radius_earth * c;
+ float dz = alt - wp->z;
+
+ *dist_xy = fabsf(dxy);
+ *dist_z = fabsf(dz);
+
+ return sqrtf(dxy * dxy + dz * dz);
} else {
return -1.0f;
}
- counter++;
-
}
/*
* Calculate distance in local frame (NED)
*/
-float mavlink_wpm_distance_to_point_local(uint16_t seq, float x, float y, float z)
+float mavlink_wpm_distance_to_point_local(uint16_t seq, float x, float y, float z, float *dist_xy, float *dist_z)
{
if (seq < wpm->size) {
mavlink_mission_item_t *cur = &(wpm->waypoints[seq]);
@@ -336,88 +296,182 @@ float mavlink_wpm_distance_to_point_local(uint16_t seq, float x, float y, float
float dy = (cur->y - y);
float dz = (cur->z - z);
- return sqrt(dx * dx + dy * dy + dz * dz);
+ *dist_xy = sqrtf(dx * dx + dy * dy);
+ *dist_z = fabsf(dz);
+
+ return sqrtf(dx * dx + dy * dy + dz * dz);
} else {
return -1.0f;
}
}
-void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_s *global_pos, struct vehicle_local_position_s *local_pos)
+void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_s *global_pos, struct vehicle_local_position_s *local_pos, float turn_distance)
{
static uint16_t counter;
- // Do not flood the precious wireless link with debug data
- // if (wpm->size > 0 && counter % 10 == 0) {
- // printf("Currect active waypoint id: %i\n", wpm->current_active_wp_id);
- // }
-
+ if ((!global_pos->valid && !local_pos->xy_valid) ||
+ /* no waypoint */
+ wpm->size == 0) {
+ /* nothing to check here, return */
+ return;
+ }
if (wpm->current_active_wp_id < wpm->size) {
- float orbit = wpm->waypoints[wpm->current_active_wp_id].param2;
+ float orbit;
+ if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT) {
+
+ orbit = wpm->waypoints[wpm->current_active_wp_id].param2;
+
+ } else if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM) {
+
+ orbit = wpm->waypoints[wpm->current_active_wp_id].param3;
+ } else {
+
+ // XXX set default orbit via param
+ orbit = 15.0f;
+ }
+
+ /* keep vertical orbit */
+ float vertical_switch_distance = orbit;
+
+ /* Take the larger turn distance - orbit or turn_distance */
+ if (orbit < turn_distance)
+ orbit = turn_distance;
+
int coordinate_frame = wpm->waypoints[wpm->current_active_wp_id].frame;
float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
if (coordinate_frame == (int)MAV_FRAME_GLOBAL) {
- dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->alt);
+ dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->alt, &dist_xy, &dist_z);
} else if (coordinate_frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
- dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, global_pos->lat, global_pos->lon, global_pos->relative_alt);
+ dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->relative_alt, &dist_xy, &dist_z);
} else if (coordinate_frame == (int)MAV_FRAME_LOCAL_ENU || coordinate_frame == (int)MAV_FRAME_LOCAL_NED) {
- dist = mavlink_wpm_distance_to_point_local(wpm->current_active_wp_id, local_pos->x, local_pos->y, local_pos->z);
+ dist = mavlink_wpm_distance_to_point_local(wpm->current_active_wp_id, local_pos->x, local_pos->y, local_pos->z, &dist_xy, &dist_z);
} else if (coordinate_frame == (int)MAV_FRAME_MISSION) {
/* Check if conditions of mission item are satisfied */
// XXX TODO
}
- if (dist >= 0.f && dist <= orbit /*&& wpm->yaw_reached*/) { //TODO implement yaw
+ if (dist >= 0.f && dist_xy <= orbit && dist_z >= 0.0f && dist_z <= vertical_switch_distance) {
wpm->pos_reached = true;
-
- if (counter % 100 == 0)
- printf("Setpoint reached: %0.4f, orbit: %.4f\n", dist, orbit);
}
-// else
-// {
-// if(counter % 100 == 0)
-// printf("Setpoint not reached yet: %0.4f, orbit: %.4f, coordinate frame: %d\n",dist, orbit, coordinate_frame);
-// }
+ // check if required yaw reached
+ float yaw_sp = _wrap_pi(wpm->waypoints[wpm->current_active_wp_id].param4 / 180.0f * FM_PI);
+ float yaw_err = _wrap_pi(yaw_sp - local_pos->yaw);
+ if (fabsf(yaw_err) < 0.05f) {
+ wpm->yaw_reached = true;
+ }
}
//check if the current waypoint was reached
- if (wpm->pos_reached /*wpm->yaw_reached &&*/ && !wpm->idle) {
+ if (wpm->pos_reached && /*wpm->yaw_reached &&*/ !wpm->idle) {
if (wpm->current_active_wp_id < wpm->size) {
mavlink_mission_item_t *cur_wp = &(wpm->waypoints[wpm->current_active_wp_id]);
if (wpm->timestamp_firstinside_orbit == 0) {
// Announce that last waypoint was reached
- printf("Reached waypoint %u for the first time \n", cur_wp->seq);
mavlink_wpm_send_waypoint_reached(cur_wp->seq);
wpm->timestamp_firstinside_orbit = now;
}
// check if the MAV was long enough inside the waypoint orbit
//if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000))
- if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param2 * 1000) {
- printf("Reached waypoint %u long enough \n", cur_wp->seq);
+
+ bool time_elapsed = false;
+
+ if (now - wpm->timestamp_firstinside_orbit >= cur_wp->param1 * 1000 * 1000) {
+ time_elapsed = true;
+ } else if (cur_wp->command == (int)MAV_CMD_NAV_TAKEOFF) {
+ time_elapsed = true;
+ }
+
+ if (time_elapsed) {
+
+ /* safeguard against invalid missions with last wp autocontinue on */
+ if (wpm->current_active_wp_id == wpm->size - 1) {
+ /* stop handling missions here */
+ cur_wp->autocontinue = false;
+ }
if (cur_wp->autocontinue) {
- cur_wp->current = 0;
- if (wpm->current_active_wp_id == wpm->size - 1 && wpm->size > 1) {
- /* the last waypoint was reached, if auto continue is
- * activated restart the waypoint list from the beginning
- */
- wpm->current_active_wp_id = 0;
+ cur_wp->current = 0;
- } else {
- if ((uint16_t)(wpm->current_active_wp_id + 1) < wpm->size)
- wpm->current_active_wp_id++;
+ float navigation_lat = -1.0f;
+ float navigation_lon = -1.0f;
+ float navigation_alt = -1.0f;
+ int navigation_frame = -1;
+
+ /* initialize to current position in case we don't find a suitable navigation waypoint */
+ if (global_pos->valid) {
+ navigation_lat = global_pos->lat/1e7;
+ navigation_lon = global_pos->lon/1e7;
+ navigation_alt = global_pos->alt;
+ navigation_frame = MAV_FRAME_GLOBAL;
+ } else if (local_pos->xy_valid && local_pos->z_valid) {
+ navigation_lat = local_pos->x;
+ navigation_lon = local_pos->y;
+ navigation_alt = local_pos->z;
+ navigation_frame = MAV_FRAME_LOCAL_NED;
}
+ /* guard against missions without final land waypoint */
+ /* only accept supported navigation waypoints, skip unknown ones */
+ do {
+
+ /* pick up the last valid navigation waypoint, this will be one we hold on to after the mission */
+ if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_TAKEOFF) {
+
+ /* this is a navigation waypoint */
+ navigation_frame = cur_wp->frame;
+ navigation_lat = cur_wp->x;
+ navigation_lon = cur_wp->y;
+ navigation_alt = cur_wp->z;
+ }
+
+ if (wpm->current_active_wp_id == wpm->size - 1) {
+
+ /* if we're not landing at the last nav waypoint, we're falling back to loiter */
+ if (wpm->waypoints[wpm->current_active_wp_id].command != (int)MAV_CMD_NAV_LAND) {
+ /* the last waypoint was reached, if auto continue is
+ * activated AND it is NOT a land waypoint, keep the system loitering there.
+ */
+ cur_wp->command = MAV_CMD_NAV_LOITER_UNLIM;
+ cur_wp->param3 = 20.0f; // XXX magic number 20 m loiter radius
+ cur_wp->frame = navigation_frame;
+ cur_wp->x = navigation_lat;
+ cur_wp->y = navigation_lon;
+ cur_wp->z = navigation_alt;
+ }
+
+ /* we risk an endless loop for missions without navigation waypoints, abort. */
+ break;
+
+ } else {
+ if ((uint16_t)(wpm->current_active_wp_id + 1) < wpm->size)
+ wpm->current_active_wp_id++;
+ }
+
+ } while (!(wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM));
+
// Fly to next waypoint
wpm->timestamp_firstinside_orbit = 0;
mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
@@ -438,7 +492,7 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
}
-int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_position_s *global_position, struct vehicle_local_position_s *local_position)
+int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_position_s *global_position, struct vehicle_local_position_s *local_position, struct navigation_capabilities_s *nav_cap)
{
/* check for timed-out operations */
if (now - wpm->timestamp_lastaction > wpm->timeout && wpm->current_state != MAVLINK_WPM_STATE_IDLE) {
@@ -461,12 +515,7 @@ int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_positio
}
}
- // Do NOT continously send the current WP, since we're not loosing messages
- // if (now - wpm->timestamp_last_send_setpoint > wpm->delay_setpoint && wpm->current_active_wp_id < wpm->size) {
- // mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
- // }
-
- check_waypoints_reached(now, global_position , local_position);
+ check_waypoints_reached(now, global_position, local_position, nav_cap->turn_distance);
return OK;
}
@@ -477,115 +526,6 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
uint64_t now = mavlink_missionlib_get_system_timestamp();
switch (msg->msgid) {
-// case MAVLINK_MSG_ID_ATTITUDE:
-// {
-// if(msg->sysid == mavlink_system.sysid && wpm->current_active_wp_id < wpm->size)
-// {
-// mavlink_mission_item_t *wp = &(wpm->waypoints[wpm->current_active_wp_id]);
-// if(wp->frame == MAV_FRAME_LOCAL_ENU || wp->frame == MAV_FRAME_LOCAL_NED)
-// {
-// mavlink_attitude_t att;
-// mavlink_msg_attitude_decode(msg, &att);
-// float yaw_tolerance = wpm->accept_range_yaw;
-// //compare current yaw
-// if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*FM_PI)
-// {
-// if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4)
-// wpm->yaw_reached = true;
-// }
-// else if(att.yaw - yaw_tolerance < 0.0f)
-// {
-// float lowerBound = 360.0f + att.yaw - yaw_tolerance;
-// if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance)
-// wpm->yaw_reached = true;
-// }
-// else
-// {
-// float upperBound = att.yaw + yaw_tolerance - 2.f*FM_PI;
-// if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound)
-// wpm->yaw_reached = true;
-// }
-// }
-// }
-// break;
-// }
-//
-// case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
-// {
-// if(msg->sysid == mavlink_system.sysid && wpm->current_active_wp_id < wpm->size)
-// {
-// mavlink_mission_item_t *wp = &(wpm->waypoints[wpm->current_active_wp_id]);
-//
-// if(wp->frame == MAV_FRAME_LOCAL_ENU || MAV_FRAME_LOCAL_NED)
-// {
-// mavlink_local_position_ned_t pos;
-// mavlink_msg_local_position_ned_decode(msg, &pos);
-// //// if (debug) // printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z);
-//
-// wpm->pos_reached = false;
-//
-// // compare current position (given in message) with current waypoint
-// float orbit = wp->param1;
-//
-// float dist;
-//// if (wp->param2 == 0)
-//// {
-//// // FIXME segment distance
-//// //dist = mavlink_wpm_distance_to_segment(current_active_wp_id, pos.x, pos.y, pos.z);
-//// }
-//// else
-//// {
-// dist = mavlink_wpm_distance_to_point(wpm->current_active_wp_id, pos.x, pos.y, pos.z);
-//// }
-//
-// if (dist >= 0.f && dist <= orbit && wpm->yaw_reached)
-// {
-// wpm->pos_reached = true;
-// }
-// }
-// }
-// break;
-// }
-
-// case MAVLINK_MSG_ID_CMD: // special action from ground station
-// {
-// mavlink_cmd_t action;
-// mavlink_msg_cmd_decode(msg, &action);
-// if(action.target == mavlink_system.sysid)
-// {
-// // if (verbose) std::cerr << "Waypoint: received message with action " << action.action << std::endl;
-// switch (action.action)
-// {
-// // case MAV_ACTION_LAUNCH:
-// // // if (verbose) std::cerr << "Launch received" << std::endl;
-// // current_active_wp_id = 0;
-// // if (wpm->size>0)
-// // {
-// // setActive(waypoints[current_active_wp_id]);
-// // }
-// // else
-// // // if (verbose) std::cerr << "No launch, waypointList empty" << std::endl;
-// // break;
-//
-// // case MAV_ACTION_CONTINUE:
-// // // if (verbose) std::c
-// // err << "Continue received" << std::endl;
-// // idle = false;
-// // setActive(waypoints[current_active_wp_id]);
-// // break;
-//
-// // case MAV_ACTION_HALT:
-// // // if (verbose) std::cerr << "Halt received" << std::endl;
-// // idle = true;
-// // break;
-//
-// // default:
-// // // if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl;
-// // break;
-// }
-// }
-// break;
-// }
case MAVLINK_MSG_ID_MISSION_ACK: {
mavlink_mission_ack_t wpa;
@@ -596,26 +536,16 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
if (wpm->current_wp_id == wpm->size - 1) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
-#else
- if (MAVLINK_WPM_VERBOSE) printf("Received ACK after having sent last waypoint, going to state MAVLINK_WPM_STATE_IDLE\n");
+ mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
-#endif
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
wpm->current_wp_id = 0;
}
}
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
-
-#endif
}
break;
@@ -643,13 +573,8 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
}
}
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("NEW WP SET");
-#else
- if (MAVLINK_WPM_VERBOSE) printf("New current waypoint %u\n", wpm->current_active_wp_id);
-
-#endif
wpm->yaw_reached = false;
wpm->pos_reached = false;
mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
@@ -657,33 +582,16 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
wpm->timestamp_firstinside_orbit = 0;
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT: Index out of bounds\n");
-
-#endif
}
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE NOT IN IDLE STATE\n");
-#endif
}
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
-
-#endif
}
break;
@@ -1130,5 +1038,5 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
}
}
- check_waypoints_reached(now, global_pos, local_pos);
+ // check_waypoints_reached(now, global_pos, local_pos);
}
diff --git a/src/modules/mavlink/waypoints.h b/src/modules/mavlink/waypoints.h
index c32ab32e5..d7d6b31dc 100644
--- a/src/modules/mavlink/waypoints.h
+++ b/src/modules/mavlink/waypoints.h
@@ -47,14 +47,15 @@
#include <v1.0/mavlink_types.h>
-#ifndef MAVLINK_SEND_UART_BYTES
-#define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
-#endif
-extern mavlink_system_t mavlink_system;
-#include <v1.0/common/mavlink.h>
+// #ifndef MAVLINK_SEND_UART_BYTES
+// #define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
+// #endif
+//extern mavlink_system_t mavlink_system;
+#include "mavlink_bridge_header.h"
#include <stdbool.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/navigation_capabilities.h>
// FIXME XXX - TO BE MOVED TO XML
enum MAVLINK_WPM_STATES {
@@ -120,7 +121,7 @@ typedef struct mavlink_wpm_storage mavlink_wpm_storage;
void mavlink_wpm_init(mavlink_wpm_storage *state);
int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_position_s *global_position,
- struct vehicle_local_position_s *local_pos);
+ struct vehicle_local_position_s *local_pos, struct navigation_capabilities_s *nav_cap);
void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehicle_global_position_s *global_pos ,
struct vehicle_local_position_s *local_pos);
diff --git a/src/modules/mavlink_onboard/mavlink.c b/src/modules/mavlink_onboard/mavlink.c
index cb6d6b16a..0edb53a3e 100644
--- a/src/modules/mavlink_onboard/mavlink.c
+++ b/src/modules/mavlink_onboard/mavlink.c
@@ -49,7 +49,6 @@
#include <mqueue.h>
#include <string.h>
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
#include <time.h>
#include <float.h>
@@ -168,12 +167,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
case 921600: speed = B921600; break;
default:
- fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
+ warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600", baud);
return -EINVAL;
}
/* open uart */
- printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
+ warnx("UART is %s, baudrate is %d", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@@ -184,7 +183,7 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
if (strcmp(uart_name, "/dev/ttyACM0") != OK) {
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
+ warnx("ERROR getting baudrate / termios config for %s: %d", uart_name, termios_state);
close(uart);
return -1;
}
@@ -197,14 +196,14 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)", uart_name, termios_state);
close(uart);
return -1;
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)", uart_name);
close(uart);
return -1;
}
@@ -274,18 +273,18 @@ void mavlink_update_system(void)
}
void
-get_mavlink_mode_and_state(const struct vehicle_status_s *v_status, const struct actuator_armed_s *armed,
+get_mavlink_mode_and_state(const struct vehicle_control_mode_s *control_mode, const struct actuator_armed_s *armed,
uint8_t *mavlink_state, uint8_t *mavlink_mode)
{
/* reset MAVLink mode bitfield */
*mavlink_mode = 0;
/* set mode flags independent of system state */
- if (v_status->flag_control_manual_enabled) {
+ if (control_mode->flag_control_manual_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
- if (v_status->flag_hil_enabled) {
+ if (control_mode->flag_system_hil_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_HIL_ENABLED;
}
@@ -296,61 +295,67 @@ get_mavlink_mode_and_state(const struct vehicle_status_s *v_status, const struct
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
}
- switch (v_status->state_machine) {
- case SYSTEM_STATE_PREFLIGHT:
- if (v_status->flag_preflight_gyro_calibration ||
- v_status->flag_preflight_mag_calibration ||
- v_status->flag_preflight_accel_calibration) {
- *mavlink_state = MAV_STATE_CALIBRATING;
- } else {
- *mavlink_state = MAV_STATE_UNINIT;
- }
- break;
-
- case SYSTEM_STATE_STANDBY:
- *mavlink_state = MAV_STATE_STANDBY;
- break;
-
- case SYSTEM_STATE_GROUND_READY:
- *mavlink_state = MAV_STATE_ACTIVE;
- break;
-
- case SYSTEM_STATE_MANUAL:
- *mavlink_state = MAV_STATE_ACTIVE;
- *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
- break;
-
- case SYSTEM_STATE_STABILIZED:
- *mavlink_state = MAV_STATE_ACTIVE;
- *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
- break;
-
- case SYSTEM_STATE_AUTO:
- *mavlink_state = MAV_STATE_ACTIVE;
+ if (control_mode->flag_control_velocity_enabled) {
*mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
- break;
-
- case SYSTEM_STATE_MISSION_ABORT:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_EMCY_LANDING:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_EMCY_CUTOFF:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_GROUND_ERROR:
- *mavlink_state = MAV_STATE_EMERGENCY;
- break;
-
- case SYSTEM_STATE_REBOOT:
- *mavlink_state = MAV_STATE_POWEROFF;
- break;
+ } else {
+ *mavlink_mode &= ~MAV_MODE_FLAG_GUIDED_ENABLED;
}
+// switch (v_status->state_machine) {
+// case SYSTEM_STATE_PREFLIGHT:
+// if (v_status->flag_preflight_gyro_calibration ||
+// v_status->flag_preflight_mag_calibration ||
+// v_status->flag_preflight_accel_calibration) {
+// *mavlink_state = MAV_STATE_CALIBRATING;
+// } else {
+// *mavlink_state = MAV_STATE_UNINIT;
+// }
+// break;
+//
+// case SYSTEM_STATE_STANDBY:
+// *mavlink_state = MAV_STATE_STANDBY;
+// break;
+//
+// case SYSTEM_STATE_GROUND_READY:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// break;
+//
+// case SYSTEM_STATE_MANUAL:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// *mavlink_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+// break;
+//
+// case SYSTEM_STATE_STABILIZED:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// *mavlink_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
+// break;
+//
+// case SYSTEM_STATE_AUTO:
+// *mavlink_state = MAV_STATE_ACTIVE;
+// *mavlink_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
+// break;
+//
+// case SYSTEM_STATE_MISSION_ABORT:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_EMCY_LANDING:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_EMCY_CUTOFF:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_GROUND_ERROR:
+// *mavlink_state = MAV_STATE_EMERGENCY;
+// break;
+//
+// case SYSTEM_STATE_REBOOT:
+// *mavlink_state = MAV_STATE_POWEROFF;
+// break;
+// }
+
}
/**
@@ -362,7 +367,9 @@ int mavlink_thread_main(int argc, char *argv[])
char *device_name = "/dev/ttyS1";
baudrate = 57600;
+ /* XXX this is never written? */
struct vehicle_status_s v_status;
+ struct vehicle_control_mode_s control_mode;
struct actuator_armed_s armed;
/* work around some stupidity in task_create's argv handling */
@@ -431,19 +438,19 @@ int mavlink_thread_main(int argc, char *argv[])
/* translate the current system state to mavlink state and mode */
uint8_t mavlink_state = 0;
uint8_t mavlink_mode = 0;
- get_mavlink_mode_and_state(&v_status, &armed, &mavlink_state, &mavlink_mode);
+ get_mavlink_mode_and_state(&control_mode, &armed, &mavlink_state, &mavlink_mode);
/* send heartbeat */
- mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
+ mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.navigation_state, mavlink_state);
/* send status (values already copied in the section above) */
mavlink_msg_sys_status_send(chan,
v_status.onboard_control_sensors_present,
v_status.onboard_control_sensors_enabled,
v_status.onboard_control_sensors_health,
- v_status.load,
- v_status.voltage_battery * 1000.0f,
- v_status.current_battery * 1000.0f,
+ v_status.load * 1000.0f,
+ v_status.battery_voltage * 1000.0f,
+ v_status.battery_current * 1000.0f,
v_status.battery_remaining,
v_status.drop_rate_comm,
v_status.errors_comm,
@@ -474,9 +481,9 @@ int mavlink_thread_main(int argc, char *argv[])
static void
usage()
{
- fprintf(stderr, "usage: mavlink start [-d <devicename>] [-b <baud rate>]\n"
- " mavlink stop\n"
- " mavlink status\n");
+ fprintf(stderr, "usage: mavlink_onboard start [-d <devicename>] [-b <baud rate>]\n"
+ " mavlink_onboard stop\n"
+ " mavlink_onboard status\n");
exit(1);
}
@@ -492,7 +499,7 @@ int mavlink_onboard_main(int argc, char *argv[])
/* this is not an error */
if (thread_running)
- errx(0, "mavlink already running\n");
+ errx(0, "already running");
thread_should_exit = false;
mavlink_task = task_spawn_cmd("mavlink_onboard",
@@ -509,7 +516,7 @@ int mavlink_onboard_main(int argc, char *argv[])
while (thread_running) {
usleep(200000);
}
- warnx("terminated.");
+ warnx("terminated");
exit(0);
}
diff --git a/src/modules/mavlink_onboard/mavlink_bridge_header.h b/src/modules/mavlink_onboard/mavlink_bridge_header.h
index 3ad3bb617..b72bbb2b1 100644
--- a/src/modules/mavlink_onboard/mavlink_bridge_header.h
+++ b/src/modules/mavlink_onboard/mavlink_bridge_header.h
@@ -78,4 +78,6 @@ extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, int len
mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan);
+#include <v1.0/common/mavlink.h>
+
#endif /* MAVLINK_BRIDGE_HEADER_H */
diff --git a/src/modules/mavlink_onboard/mavlink_receiver.c b/src/modules/mavlink_onboard/mavlink_receiver.c
index 0acbea675..4658bcc1d 100644
--- a/src/modules/mavlink_onboard/mavlink_receiver.c
+++ b/src/modules/mavlink_onboard/mavlink_receiver.c
@@ -50,7 +50,6 @@
#include <mqueue.h>
#include <string.h>
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
#include <time.h>
#include <float.h>
@@ -101,11 +100,11 @@ handle_message(mavlink_message_t *msg)
mavlink_msg_command_long_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))) {
+ || (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 */
- printf("[mavlink] Terminating .. \n");
+ warnx("terminating...");
fflush(stdout);
usleep(50000);
@@ -133,6 +132,7 @@ handle_message(mavlink_message_t *msg)
if (cmd_pub <= 0) {
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
}
+
/* publish */
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
}
@@ -157,6 +157,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic is advertised */
if (flow_pub <= 0) {
flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
+
} else {
/* publish */
orb_publish(ORB_ID(optical_flow), flow_pub, &f);
@@ -187,6 +188,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic is advertised */
if (cmd_pub <= 0) {
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
+
} else {
/* create command */
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
@@ -204,6 +206,7 @@ handle_message(mavlink_message_t *msg)
if (vicon_position_pub <= 0) {
vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);
+
} else {
orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
}
@@ -220,7 +223,7 @@ handle_message(mavlink_message_t *msg)
/* switch to a receiving link mode */
gcs_link = false;
- /*
+ /*
* rate control mode - defined by MAVLink
*/
@@ -228,33 +231,37 @@ handle_message(mavlink_message_t *msg)
bool ml_armed = false;
switch (quad_motors_setpoint.mode) {
- case 0:
- ml_armed = false;
- break;
- case 1:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
- ml_armed = true;
-
- break;
- case 2:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
- ml_armed = true;
-
- break;
- case 3:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
- break;
- case 4:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
- break;
+ case 0:
+ ml_armed = false;
+ break;
+
+ case 1:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
+ ml_armed = true;
+
+ break;
+
+ case 2:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
+ ml_armed = true;
+
+ break;
+
+ case 3:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
+ break;
+
+ case 4:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
+ break;
}
- offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid-1] / (float)INT16_MAX;
- offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid-1] / (float)INT16_MAX;
- offboard_control_sp.p3= (float)quad_motors_setpoint.yaw[mavlink_system.sysid-1] / (float)INT16_MAX;
- offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid-1]/(float)UINT16_MAX;
+ offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
+ offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
+ offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
+ offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
- if (quad_motors_setpoint.thrust[mavlink_system.sysid-1] == 0) {
+ if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
ml_armed = false;
}
@@ -266,6 +273,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic has to be advertised */
if (offboard_control_sp_pub <= 0) {
offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
+
} else {
/* Publish */
orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
@@ -282,31 +290,36 @@ handle_message(mavlink_message_t *msg)
static void *
receive_thread(void *arg)
{
- int uart_fd = *((int*)arg);
+ int uart_fd = *((int *)arg);
const int timeout = 1000;
- uint8_t ch;
+ uint8_t buf[32];
mavlink_message_t msg;
- prctl(PR_SET_NAME, "mavlink offb rcv", getpid());
+ prctl(PR_SET_NAME, "mavlink_onboard_rcv", getpid());
- while (!thread_should_exit) {
+ struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
- struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
+ ssize_t nread = 0;
+ while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
- /* non-blocking read until buffer is empty */
- int nread = 0;
+ if (nread < sizeof(buf)) {
+ /* to avoid reading very small chunks wait for data before reading */
+ usleep(1000);
+ }
- do {
- nread = read(uart_fd, &ch, 1);
+ /* non-blocking read. read may return negative values */
+ nread = read(uart_fd, buf, sizeof(buf));
- if (mavlink_parse_char(chan, ch, &msg, &status)) { //parse the char
+ /* if read failed, this loop won't execute */
+ for (ssize_t i = 0; i < nread; i++) {
+ if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
/* handle generic messages and commands */
handle_message(&msg);
}
- } while (nread > 0);
+ }
}
}
@@ -320,12 +333,12 @@ receive_start(int uart)
pthread_attr_init(&receiveloop_attr);
struct sched_param param;
- param.sched_priority = SCHED_PRIORITY_MAX - 40;
- (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
+ param.sched_priority = SCHED_PRIORITY_MAX - 40;
+ (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2048);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
return thread;
-} \ No newline at end of file
+}
diff --git a/src/modules/mavlink_onboard/orb_topics.h b/src/modules/mavlink_onboard/orb_topics.h
index f18f56243..1b49c9ce4 100644
--- a/src/modules/mavlink_onboard/orb_topics.h
+++ b/src/modules/mavlink_onboard/orb_topics.h
@@ -52,9 +52,11 @@
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_position_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/debug_key_value.h>
#include <drivers/drv_rc_input.h>
@@ -69,7 +71,7 @@ struct mavlink_subscriptions {
int act_3_sub;
int gps_sub;
int man_control_sp_sub;
- int armed_sub;
+ int safety_sub;
int actuators_sub;
int local_pos_sub;
int spa_sub;
diff --git a/src/modules/mavlink_onboard/util.h b/src/modules/mavlink_onboard/util.h
index 38a4db372..c84b6fd26 100644
--- a/src/modules/mavlink_onboard/util.h
+++ b/src/modules/mavlink_onboard/util.h
@@ -50,5 +50,6 @@ extern volatile bool thread_should_exit;
/**
* Translate the custom state into standard mavlink modes and state.
*/
-extern void get_mavlink_mode_and_state(const struct vehicle_status_s *v_status, const struct actuator_armed_s *armed,
+extern void
+get_mavlink_mode_and_state(const struct vehicle_control_mode_s *control_mode, const struct actuator_armed_s *armed,
uint8_t *mavlink_state, uint8_t *mavlink_mode);
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index 99f25cfe9..60a211817 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -2,6 +2,7 @@
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,6 +39,7 @@
* Implementation of multirotor attitude control main loop.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
@@ -57,12 +59,13 @@
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <drivers/drv_gyro.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
@@ -74,333 +77,311 @@
#include "multirotor_attitude_control.h"
#include "multirotor_rate_control.h"
-PARAM_DEFINE_FLOAT(MC_RCLOSS_THR, 0.0f); // This defines the throttle when the RC signal is lost.
-
__EXPORT int multirotor_att_control_main(int argc, char *argv[]);
static bool thread_should_exit;
static int mc_task;
static bool motor_test_mode = false;
-
-static orb_advert_t actuator_pub;
-
-static struct vehicle_status_s state;
+static const float min_takeoff_throttle = 0.3f;
+static const float yaw_deadzone = 0.01f;
static int
mc_thread_main(int argc, char *argv[])
{
/* declare and safely initialize all structs */
- memset(&state, 0, sizeof(state));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
memset(&att_sp, 0, sizeof(att_sp));
- struct manual_control_setpoint_s manual;
- memset(&manual, 0, sizeof(manual));
- struct sensor_combined_s raw;
- memset(&raw, 0, sizeof(raw));
struct offboard_control_setpoint_s offboard_sp;
memset(&offboard_sp, 0, sizeof(offboard_sp));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
+ struct manual_control_setpoint_s manual;
+ memset(&manual, 0, sizeof(manual));
+ struct sensor_combined_s sensor;
+ memset(&sensor, 0, sizeof(sensor));
struct vehicle_rates_setpoint_s rates_sp;
memset(&rates_sp, 0, sizeof(rates_sp));
-
+ struct vehicle_status_s status;
+ memset(&status, 0, sizeof(status));
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
- /* subscribe to attitude, motor setpoints and system state */
- int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int param_sub = orb_subscribe(ORB_ID(parameter_update));
- int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
- int setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- int state_sub = orb_subscribe(ORB_ID(vehicle_status));
- int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
-
- /*
- * Do not rate-limit the loop to prevent aliasing
- * if rate-limiting would be desired later, the line below would
- * enable it.
- *
- * rate-limit the attitude subscription to 200Hz to pace our loop
- * orb_set_interval(att_sub, 5);
- */
- struct pollfd fds[2] = {
- { .fd = att_sub, .events = POLLIN },
- { .fd = param_sub, .events = POLLIN }
- };
+ /* subscribe */
+ int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
+ int vehicle_attitude_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ int offboard_control_setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
+ int vehicle_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ int manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+ int vehicle_rates_setpoint_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
+ int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
/* publish actuator controls */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
actuators.control[i] = 0.0f;
}
- actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
+ orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
orb_advert_t rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
- int rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
/* register the perf counter */
perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "multirotor_att_control_runtime");
perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "multirotor_att_control_interval");
perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "multirotor_att_control_err");
- /* welcome user */
- printf("[multirotor_att_control] starting\n");
+ warnx("starting");
/* store last control mode to detect mode switches */
- bool flag_control_manual_enabled = false;
- bool flag_control_attitude_enabled = false;
- bool flag_system_armed = false;
-
- /* store if yaw position or yaw speed has been changed */
bool control_yaw_position = true;
+ bool reset_yaw_sp = true;
- /* store if we stopped a yaw movement */
- bool first_time_after_yaw_speed_control = true;
-
- /* prepare the handle for the failsafe throttle */
- param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
- float failsafe_throttle = 0.0f;
-
+ struct pollfd fds[1] = {
+ { .fd = vehicle_attitude_sub, .events = POLLIN },
+ };
while (!thread_should_exit) {
/* wait for a sensor update, check for exit condition every 500 ms */
- int ret = poll(fds, 2, 500);
+ int ret = poll(fds, 1, 500);
if (ret < 0) {
/* poll error, count it in perf */
perf_count(mc_err_perf);
- } else if (ret == 0) {
- /* no return value, ignore */
- } else {
+ } else if (ret > 0) {
+ /* only run controller if attitude changed */
+ perf_begin(mc_loop_perf);
- /* only update parameters if they changed */
- if (fds[1].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), param_sub, &update);
+ /* attitude */
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+ bool updated;
+
+ /* parameters */
+ orb_check(parameter_update_sub, &updated);
+
+ if (updated) {
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
/* update parameters */
- // XXX no params here yet
}
- /* only run controller if attitude changed */
- if (fds[0].revents & POLLIN) {
+ /* control mode */
+ orb_check(vehicle_control_mode_sub, &updated);
- perf_begin(mc_loop_perf);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sub, &control_mode);
+ }
- /* get a local copy of system state */
- bool updated;
- orb_check(state_sub, &updated);
+ /* manual control setpoint */
+ orb_check(manual_control_setpoint_sub, &updated);
- if (updated) {
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
- }
+ if (updated) {
+ orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual);
+ }
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
- /* get a local copy of attitude setpoint */
- orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp);
- /* get a local copy of rates setpoint */
- orb_check(setpoint_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(offboard_control_setpoint), setpoint_sub, &offboard_sp);
- }
+ /* attitude setpoint */
+ orb_check(vehicle_attitude_setpoint_sub, &updated);
- /* get a local copy of the current sensor values */
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub, &att_sp);
+ }
+ /* offboard control setpoint */
+ orb_check(offboard_control_setpoint_sub, &updated);
- /** STEP 1: Define which input is the dominating control input */
- if (state.flag_control_offboard_enabled) {
- /* offboard inputs */
- if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
- rates_sp.roll = offboard_sp.p1;
- rates_sp.pitch = offboard_sp.p2;
- rates_sp.yaw = offboard_sp.p3;
- rates_sp.thrust = offboard_sp.p4;
-// printf("thrust_rate=%8.4f\n",offboard_sp.p4);
- rates_sp.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
-
- } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
- att_sp.roll_body = offboard_sp.p1;
- att_sp.pitch_body = offboard_sp.p2;
- att_sp.yaw_body = offboard_sp.p3;
- att_sp.thrust = offboard_sp.p4;
-// printf("thrust_att=%8.4f\n",offboard_sp.p4);
- att_sp.timestamp = hrt_absolute_time();
- /* STEP 2: publish the result to the vehicle actuators */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- }
+ if (updated) {
+ orb_copy(ORB_ID(offboard_control_setpoint), offboard_control_setpoint_sub, &offboard_sp);
+ }
+
+ /* vehicle status */
+ orb_check(vehicle_status_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &status);
+ }
+ /* sensors */
+ orb_check(sensor_combined_sub, &updated);
- } else if (state.flag_control_manual_enabled) {
+ if (updated) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+ }
+
+ /* set flag to safe value */
+ control_yaw_position = true;
- if (state.flag_control_attitude_enabled) {
+ /* reset yaw setpoint if not armed */
+ if (!control_mode.flag_armed) {
+ reset_yaw_sp = true;
+ }
+
+ /* define which input is the dominating control input */
+ if (control_mode.flag_control_offboard_enabled) {
+ /* offboard inputs */
+ if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
+ rates_sp.roll = offboard_sp.p1;
+ rates_sp.pitch = offboard_sp.p2;
+ rates_sp.yaw = offboard_sp.p3;
+ rates_sp.thrust = offboard_sp.p4;
+ rates_sp.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
- /* initialize to current yaw if switching to manual or att control */
- if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
- state.flag_control_manual_enabled != flag_control_manual_enabled ||
- state.flag_system_armed != flag_system_armed) {
- att_sp.yaw_body = att.yaw;
+ } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
+ att_sp.roll_body = offboard_sp.p1;
+ att_sp.pitch_body = offboard_sp.p2;
+ att_sp.yaw_body = offboard_sp.p3;
+ att_sp.thrust = offboard_sp.p4;
+ att_sp.timestamp = hrt_absolute_time();
+ /* publish the result to the vehicle actuators */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ }
+
+ /* reset yaw setpoint after offboard control */
+ reset_yaw_sp = true;
+
+ } else if (control_mode.flag_control_manual_enabled) {
+ /* manual input */
+ if (control_mode.flag_control_attitude_enabled) {
+ /* control attitude, update attitude setpoint depending on mode */
+ if (att_sp.thrust < 0.1f) {
+ /* no thrust, don't try to control yaw */
+ rates_sp.yaw = 0.0f;
+ control_yaw_position = false;
+
+ if (status.condition_landed) {
+ /* reset yaw setpoint if on ground */
+ reset_yaw_sp = true;
}
- static bool rc_loss_first_time = true;
-
- /* if the RC signal is lost, try to stay level and go slowly back down to ground */
- if (state.rc_signal_lost) {
- /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
- param_get(failsafe_throttle_handle, &failsafe_throttle);
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
-
- /*
- * Only go to failsafe throttle if last known throttle was
- * high enough to create some lift to make hovering state likely.
- *
- * This is to prevent that someone landing, but not disarming his
- * multicopter (throttle = 0) does not make it jump up in the air
- * if shutting down his remote.
- */
- if (isfinite(manual.throttle) && manual.throttle > 0.2f) {
- att_sp.thrust = failsafe_throttle;
-
- } else {
- att_sp.thrust = 0.0f;
- }
-
- /* keep current yaw, do not attempt to go to north orientation,
- * since if the pilot regains RC control, he will be lost regarding
- * the current orientation.
- */
- if (rc_loss_first_time)
- att_sp.yaw_body = att.yaw;
-
- rc_loss_first_time = false;
+ } else {
+ /* only move yaw setpoint if manual input is != 0 */
+ if (manual.yaw < -yaw_deadzone || yaw_deadzone < manual.yaw) {
+ /* control yaw rate */
+ control_yaw_position = false;
+ rates_sp.yaw = manual.yaw;
+ reset_yaw_sp = true; // has no effect on control, just for beautiful log
} else {
- rc_loss_first_time = true;
-
- att_sp.roll_body = manual.roll;
- att_sp.pitch_body = manual.pitch;
-
- /* set attitude if arming */
- if (!flag_control_attitude_enabled && state.flag_system_armed) {
- att_sp.yaw_body = att.yaw;
- }
-
- /* act if stabilization is active or if the (nonsense) direct pass through mode is set */
- if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS ||
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
-
- if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) {
- rates_sp.yaw = manual.yaw;
- control_yaw_position = false;
-
- } else {
- /*
- * This mode SHOULD be the default mode, which is:
- * VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS
- *
- * However, we fall back to this setting for all other (nonsense)
- * settings as well.
- */
-
- /* only move setpoint if manual input is != 0 */
- if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
- rates_sp.yaw = manual.yaw;
- control_yaw_position = false;
- first_time_after_yaw_speed_control = true;
-
- } else {
- if (first_time_after_yaw_speed_control) {
- att_sp.yaw_body = att.yaw;
- first_time_after_yaw_speed_control = false;
- }
-
- control_yaw_position = true;
- }
- }
- }
+ control_yaw_position = true;
+ }
+ }
+ if (!control_mode.flag_control_velocity_enabled) {
+ /* update attitude setpoint if not in position control mode */
+ att_sp.roll_body = manual.roll;
+ att_sp.pitch_body = manual.pitch;
+
+ if (!control_mode.flag_control_climb_rate_enabled) {
+ /* pass throttle directly if not in altitude control mode */
att_sp.thrust = manual.throttle;
- att_sp.timestamp = hrt_absolute_time();
}
+ }
- /* STEP 2: publish the controller output */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ /* reset yaw setpint to current position if needed */
+ if (reset_yaw_sp) {
+ att_sp.yaw_body = att.yaw;
+ reset_yaw_sp = false;
+ }
- if (motor_test_mode) {
- printf("testmode");
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
- att_sp.yaw_body = 0.0f;
- att_sp.thrust = 0.1f;
- att_sp.timestamp = hrt_absolute_time();
- /* STEP 2: publish the result to the vehicle actuators */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- }
+ if (motor_test_mode) {
+ printf("testmode");
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
+ att_sp.yaw_body = 0.0f;
+ att_sp.thrust = 0.1f;
+ }
- } else {
- /* manual rate inputs, from RC control or joystick */
- if (state.flag_control_rates_enabled &&
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
- rates_sp.roll = manual.roll;
+ att_sp.timestamp = hrt_absolute_time();
- rates_sp.pitch = manual.pitch;
- rates_sp.yaw = manual.yaw;
- rates_sp.thrust = manual.throttle;
- rates_sp.timestamp = hrt_absolute_time();
- }
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+
+ } else {
+ /* manual rate inputs (ACRO), from RC control or joystick */
+ if (control_mode.flag_control_rates_enabled) {
+ rates_sp.roll = manual.roll;
+ rates_sp.pitch = manual.pitch;
+ rates_sp.yaw = manual.yaw;
+ rates_sp.thrust = manual.throttle;
+ rates_sp.timestamp = hrt_absolute_time();
}
+ /* reset yaw setpoint after ACRO */
+ reset_yaw_sp = true;
}
- /** STEP 3: Identify the controller setup to run and set up the inputs correctly */
- if (state.flag_control_attitude_enabled) {
- multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position);
-
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
+ } else {
+ if (!control_mode.flag_control_auto_enabled) {
+ /* no control, try to stay on place */
+ if (!control_mode.flag_control_velocity_enabled) {
+ /* no velocity control, reset attitude setpoint */
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
+ att_sp.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ }
}
- /* measure in what intervals the controller runs */
- perf_count(mc_interval_perf);
+ /* reset yaw setpoint after non-manual control */
+ reset_yaw_sp = true;
+ }
+
+ /* check if we should we reset integrals */
+ bool reset_integral = !control_mode.flag_armed || att_sp.thrust < 0.1f; // TODO use landed status instead of throttle
+
+ /* run attitude controller if needed */
+ if (control_mode.flag_control_attitude_enabled) {
+ multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, reset_integral);
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
+ }
- float gyro[3];
+ /* measure in what intervals the controller runs */
+ perf_count(mc_interval_perf);
+ /* run rates controller if needed */
+ if (control_mode.flag_control_rates_enabled) {
/* get current rate setpoint */
- bool rates_sp_valid = false;
- orb_check(rates_sp_sub, &rates_sp_valid);
+ bool rates_sp_updated = false;
+ orb_check(vehicle_rates_setpoint_sub, &rates_sp_updated);
- if (rates_sp_valid) {
- orb_copy(ORB_ID(vehicle_rates_setpoint), rates_sp_sub, &rates_sp);
+ if (rates_sp_updated) {
+ orb_copy(ORB_ID(vehicle_rates_setpoint), vehicle_rates_setpoint_sub, &rates_sp);
}
/* apply controller */
- gyro[0] = att.rollspeed;
- gyro[1] = att.pitchspeed;
- gyro[2] = att.yawspeed;
+ float rates[3];
+ rates[0] = att.rollspeed;
+ rates[1] = att.pitchspeed;
+ rates[2] = att.yawspeed;
+ multirotor_control_rates(&rates_sp, rates, &actuators, reset_integral);
+
+ } else {
+ /* rates controller disabled, set actuators to zero for safety */
+ actuators.control[0] = 0.0f;
+ actuators.control[1] = 0.0f;
+ actuators.control[2] = 0.0f;
+ actuators.control[3] = 0.0f;
+ }
- multirotor_control_rates(&rates_sp, gyro, &actuators);
- orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
+ /* fill in manual control values */
+ actuators.control[4] = manual.flaps;
+ actuators.control[5] = manual.aux1;
+ actuators.control[6] = manual.aux2;
+ actuators.control[7] = manual.aux3;
- /* update state */
- flag_control_attitude_enabled = state.flag_control_attitude_enabled;
- flag_control_manual_enabled = state.flag_control_manual_enabled;
- flag_system_armed = state.flag_system_armed;
+ actuators.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- perf_end(mc_loop_perf);
- } /* end of poll call for attitude updates */
- } /* end of poll return value check */
+ perf_end(mc_loop_perf);
+ }
}
- printf("[multirotor att control] stopping, disarming motors.\n");
+ warnx("stopping, disarming motors");
/* kill all outputs */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
@@ -408,10 +389,9 @@ mc_thread_main(int argc, char *argv[])
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
-
- close(att_sub);
- close(state_sub);
- close(manual_sub);
+ close(vehicle_attitude_sub);
+ close(vehicle_control_mode_sub);
+ close(manual_control_setpoint_sub);
close(actuator_pub);
close(att_sp_pub);
@@ -467,11 +447,11 @@ int multirotor_att_control_main(int argc, char *argv[])
thread_should_exit = false;
mc_task = task_spawn_cmd("multirotor_att_control",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 15,
- 2048,
- mc_thread_main,
- NULL);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 15,
+ 2048,
+ mc_thread_main,
+ NULL);
exit(0);
}
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index 76dbb36d3..8245aa560 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
@@ -1,12 +1,12 @@
/****************************************************************************
*
* 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 Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * Laurens Mackay <mackayl@student.ethz.ch>
+ * Tobias Naegeli <naegelit@student.ethz.ch>
+ * Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -39,7 +39,15 @@
/*
* @file multirotor_attitude_control.c
- * Implementation of attitude controller
+ *
+ * Implementation of attitude controller for multirotors.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Laurens Mackay <mackayl@student.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include "multirotor_attitude_control.h"
@@ -54,15 +62,15 @@
#include <systemlib/param/param.h>
#include <drivers/drv_hrt.h>
-PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 2.0f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
//PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
//PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
-PARAM_DEFINE_FLOAT(MC_ATT_P, 0.2f);
+PARAM_DEFINE_FLOAT(MC_ATT_P, 6.8f);
PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
-PARAM_DEFINE_FLOAT(MC_ATT_D, 0.05f);
+PARAM_DEFINE_FLOAT(MC_ATT_D, 0.0f);
//PARAM_DEFINE_FLOAT(MC_ATT_AWU, 0.05f);
//PARAM_DEFINE_FLOAT(MC_ATT_LIM, 0.4f);
@@ -158,21 +166,17 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
}
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position)
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position, bool reset_integral)
{
static uint64_t last_run = 0;
static uint64_t last_input = 0;
float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f;
last_run = hrt_absolute_time();
if (last_input != att_sp->timestamp) {
last_input = att_sp->timestamp;
}
- static int sensor_delay;
- sensor_delay = hrt_absolute_time() - att->timestamp;
-
static int motor_skip_counter = 0;
static PID_t pitch_controller;
@@ -190,10 +194,8 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
parameters_init(&h);
parameters_update(&h, &p);
- pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, 1000.0f,
- 1000.0f, PID_MODE_DERIVATIV_SET);
- pid_init(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f,
- 1000.0f, PID_MODE_DERIVATIV_SET);
+ pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f, PID_MODE_DERIVATIV_SET, 0.0f);
+ pid_init(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f, PID_MODE_DERIVATIV_SET, 0.0f);
initialized = true;
}
@@ -208,13 +210,13 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, 1000.0f, 1000.0f);
}
- /* reset integral if on ground */
- if (att_sp->thrust < 0.1f) {
+ /* reset integrals if needed */
+ if (reset_integral) {
pid_reset_integral(&pitch_controller);
pid_reset_integral(&roll_controller);
+ //TODO pid_reset_integral(&yaw_controller);
}
-
/* calculate current control outputs */
/* control pitch (forward) output */
@@ -227,6 +229,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
if (control_yaw_position) {
/* control yaw rate */
+ // TODO use pid lib
/* positive error: rotate to right, negative error, rotate to left (NED frame) */
// yaw_error = _wrap_pi(att_sp->yaw_body - att->yaw);
@@ -244,6 +247,8 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
}
rates_sp->thrust = att_sp->thrust;
+ //need to update the timestamp now that we've touched rates_sp
+ rates_sp->timestamp = hrt_absolute_time();
motor_skip_counter++;
}
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.h b/src/modules/multirotor_att_control/multirotor_attitude_control.h
index 2cf83e443..431a435f7 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.h
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.h
@@ -1,12 +1,12 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * Laurens Mackay <mackayl@student.ethz.ch>
+ * Tobias Naegeli <naegelit@student.ethz.ch>
+ * Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -39,7 +39,15 @@
/*
* @file multirotor_attitude_control.h
- * Attitude control for multi rotors.
+ *
+ * Definition of attitude controller for multirotors.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Laurens Mackay <mackayl@student.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef MULTIROTOR_ATTITUDE_CONTROL_H_
@@ -52,6 +60,6 @@
#include <uORB/topics/actuator_controls.h>
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position);
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, bool control_yaw_position, bool reset_integral);
#endif /* MULTIROTOR_ATTITUDE_CONTROL_H_ */
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.c b/src/modules/multirotor_att_control/multirotor_rate_control.c
index deba1ac03..86ac0e4ff 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.c
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.c
@@ -1,8 +1,10 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
* Author: Tobias Naegeli <naegelit@student.ethz.ch>
* Lorenz Meier <lm@inf.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ * Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,10 +38,12 @@
/**
* @file multirotor_rate_control.c
*
- * Implementation of rate controller
+ * Implementation of rate controller for multirotors.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#include "multirotor_rate_control.h"
@@ -55,31 +59,23 @@
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
-PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.0f); /* same on Flamewheel */
-PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
-PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
-//PARAM_DEFINE_FLOAT(MC_YAWRATE_AWU, 0.0f);
-//PARAM_DEFINE_FLOAT(MC_YAWRATE_LIM, 1.0f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.005f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.2f);
-PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.0f); /* 0.15 F405 Flamewheel */
-PARAM_DEFINE_FLOAT(MC_ATTRATE_D, 0.0f);
+PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.09f);
+PARAM_DEFINE_FLOAT(MC_ATTRATE_D, 0.002f);
PARAM_DEFINE_FLOAT(MC_ATTRATE_I, 0.0f);
-//PARAM_DEFINE_FLOAT(MC_ATTRATE_AWU, 0.05f);
-//PARAM_DEFINE_FLOAT(MC_ATTRATE_LIM, 1.0f); /**< roughly < 500 deg/s limit */
struct mc_rate_control_params {
float yawrate_p;
float yawrate_d;
float yawrate_i;
- //float yawrate_awu;
- //float yawrate_lim;
float attrate_p;
float attrate_d;
float attrate_i;
- //float attrate_awu;
- //float attrate_lim;
float rate_lim;
};
@@ -89,14 +85,10 @@ struct mc_rate_control_param_handles {
param_t yawrate_p;
param_t yawrate_i;
param_t yawrate_d;
- //param_t yawrate_awu;
- //param_t yawrate_lim;
param_t attrate_p;
param_t attrate_i;
param_t attrate_d;
- //param_t attrate_awu;
- //param_t attrate_lim;
};
/**
@@ -118,14 +110,10 @@ static int parameters_init(struct mc_rate_control_param_handles *h)
h->yawrate_p = param_find("MC_YAWRATE_P");
h->yawrate_i = param_find("MC_YAWRATE_I");
h->yawrate_d = param_find("MC_YAWRATE_D");
- //h->yawrate_awu = param_find("MC_YAWRATE_AWU");
- //h->yawrate_lim = param_find("MC_YAWRATE_LIM");
h->attrate_p = param_find("MC_ATTRATE_P");
h->attrate_i = param_find("MC_ATTRATE_I");
h->attrate_d = param_find("MC_ATTRATE_D");
- //h->attrate_awu = param_find("MC_ATTRATE_AWU");
- //h->attrate_lim = param_find("MC_ATTRATE_LIM");
return OK;
}
@@ -135,29 +123,21 @@ static int parameters_update(const struct mc_rate_control_param_handles *h, stru
param_get(h->yawrate_p, &(p->yawrate_p));
param_get(h->yawrate_i, &(p->yawrate_i));
param_get(h->yawrate_d, &(p->yawrate_d));
- //param_get(h->yawrate_awu, &(p->yawrate_awu));
- //param_get(h->yawrate_lim, &(p->yawrate_lim));
param_get(h->attrate_p, &(p->attrate_p));
param_get(h->attrate_i, &(p->attrate_i));
param_get(h->attrate_d, &(p->attrate_d));
- //param_get(h->attrate_awu, &(p->attrate_awu));
- //param_get(h->attrate_lim, &(p->attrate_lim));
return OK;
}
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[], struct actuator_controls_s *actuators)
+ const float rates[], struct actuator_controls_s *actuators, bool reset_integral)
{
- static float roll_control_last = 0;
- static float pitch_control_last = 0;
static uint64_t last_run = 0;
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
static uint64_t last_input = 0;
- float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f;
-
if (last_input != rate_sp->timestamp) {
last_input = rate_sp->timestamp;
}
@@ -166,6 +146,10 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
static int motor_skip_counter = 0;
+ static PID_t pitch_rate_controller;
+ static PID_t roll_rate_controller;
+ static PID_t yaw_rate_controller;
+
static struct mc_rate_control_params p;
static struct mc_rate_control_param_handles h;
@@ -176,54 +160,36 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
parameters_init(&h);
parameters_update(&h, &p);
initialized = true;
+
+ pid_init(&pitch_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1.0f, 1.0f, PID_MODE_DERIVATIV_CALC_NO_SP, 0.003f);
+ pid_init(&roll_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1.0f, 1.0f, PID_MODE_DERIVATIV_CALC_NO_SP, 0.003f);
+ pid_init(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, 1.0f, 1.0f, PID_MODE_DERIVATIV_CALC_NO_SP, 0.003f);
}
/* load new parameters with lower rate */
if (motor_skip_counter % 2500 == 0) {
/* update parameters from storage */
parameters_update(&h, &p);
- // warnx("rate ctrl: p.yawrate_p: %8.4f, loop: %d Hz, input: %d Hz",
- // (double)p.yawrate_p, (int)(1.0f/deltaT), (int)(1.0f/dT_input));
- }
-
- /* calculate current control outputs */
-
- /* control pitch (forward) output */
- float pitch_control = p.attrate_p * (rate_sp->pitch - rates[1]) - (p.attrate_d * pitch_control_last);
-
- /* increase resilience to faulty control inputs */
- if (isfinite(pitch_control)) {
- pitch_control_last = pitch_control;
-
- } else {
- pitch_control = 0.0f;
- warnx("rej. NaN ctrl pitch");
+ pid_set_parameters(&pitch_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1.0f, 1.0f);
+ pid_set_parameters(&roll_rate_controller, p.attrate_p, p.attrate_i, p.attrate_d, 1.0f, 1.0f);
+ pid_set_parameters(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, 1.0f, 1.0f);
}
- /* control roll (left/right) output */
- float roll_control = p.attrate_p * (rate_sp->roll - rates[0]) - (p.attrate_d * roll_control_last);
-
- /* increase resilience to faulty control inputs */
- if (isfinite(roll_control)) {
- roll_control_last = roll_control;
-
- } else {
- roll_control = 0.0f;
- warnx("rej. NaN ctrl roll");
+ /* reset integrals if needed */
+ if (reset_integral) {
+ pid_reset_integral(&pitch_rate_controller);
+ pid_reset_integral(&roll_rate_controller);
+ pid_reset_integral(&yaw_rate_controller);
}
- /* control yaw rate */
- float yaw_rate_control = p.yawrate_p * (rate_sp->yaw - rates[2]);
-
- /* increase resilience to faulty control inputs */
- if (!isfinite(yaw_rate_control)) {
- yaw_rate_control = 0.0f;
- warnx("rej. NaN ctrl yaw");
- }
+ /* run pitch, roll and yaw controllers */
+ float pitch_control = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
+ float roll_control = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT);
+ float yaw_control = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT);
actuators->control[0] = roll_control;
actuators->control[1] = pitch_control;
- actuators->control[2] = yaw_rate_control;
+ actuators->control[2] = yaw_control;
actuators->control[3] = rate_sp->thrust;
motor_skip_counter++;
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.h b/src/modules/multirotor_att_control/multirotor_rate_control.h
index 03dec317a..ca7794c59 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.h
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.h
@@ -1,12 +1,12 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * Laurens Mackay <mackayl@student.ethz.ch>
+ * Tobias Naegeli <naegelit@student.ethz.ch>
+ * Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -39,7 +39,15 @@
/*
* @file multirotor_attitude_control.h
- * Attitude control for multi rotors.
+ *
+ * Definition of rate controller for multirotors.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Laurens Mackay <mackayl@student.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef MULTIROTOR_RATE_CONTROL_H_
@@ -51,6 +59,6 @@
#include <uORB/topics/actuator_controls.h>
void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[], struct actuator_controls_s *actuators);
+ const float rates[], struct actuator_controls_s *actuators, bool reset_integral);
#endif /* MULTIROTOR_RATE_CONTROL_H_ */
diff --git a/src/modules/multirotor_pos_control/module.mk b/src/modules/multirotor_pos_control/module.mk
index d04847745..bc4b48fb4 100644
--- a/src/modules/multirotor_pos_control/module.mk
+++ b/src/modules/multirotor_pos_control/module.mk
@@ -38,4 +38,5 @@
MODULE_COMMAND = multirotor_pos_control
SRCS = multirotor_pos_control.c \
- multirotor_pos_control_params.c
+ multirotor_pos_control_params.c \
+ thrust_pid.c
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index f39d11438..3d23d0c09 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,13 +35,14 @@
/**
* @file multirotor_pos_control.c
*
- * Skeleton for multirotor position controller
+ * Multirotor position controller
*/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
+#include <math.h>
#include <stdbool.h>
#include <unistd.h>
#include <fcntl.h>
@@ -52,15 +53,22 @@
#include <sys/prctl.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
+#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
-#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <systemlib/systemlib.h>
+#include <systemlib/pid/pid.h>
+#include <mavlink/mavlink_log.h>
#include "multirotor_pos_control_params.h"
+#include "thrust_pid.h"
static bool thread_should_exit = false; /**< Deamon exit flag */
@@ -79,12 +87,16 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]);
*/
static void usage(const char *reason);
-static void
-usage(const char *reason)
+static float scale_control(float ctl, float end, float dz);
+
+static float norm(float x, float y);
+
+static void usage(const char *reason)
{
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
+
+ fprintf(stderr, "usage: multirotor_pos_control {start|stop|status}\n\n");
exit(1);
}
@@ -92,9 +104,9 @@ usage(const char *reason)
* The deamon app only briefly exists to start
* the background job. The stack size assigned in the
* Makefile does only apply to this management task.
- *
+ *
* The actual stack size should be set in the call
- * to task_spawn_cmd().
+ * to task_spawn().
*/
int multirotor_pos_control_main(int argc, char *argv[])
{
@@ -104,32 +116,36 @@ int multirotor_pos_control_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("multirotor pos control already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
+ warnx("start");
thread_should_exit = false;
- deamon_task = task_spawn_cmd("multirotor pos control",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 60,
- 4096,
- multirotor_pos_control_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ deamon_task = task_spawn_cmd("multirotor_pos_control",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 60,
+ 4096,
+ multirotor_pos_control_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
}
if (!strcmp(argv[1], "stop")) {
+ warnx("stop");
thread_should_exit = true;
exit(0);
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tmultirotor pos control app is running\n");
+ warnx("app is running");
+
} else {
- printf("\tmultirotor pos control app not started\n");
+ warnx("app not started");
}
+
exit(0);
}
@@ -137,98 +153,534 @@ int multirotor_pos_control_main(int argc, char *argv[])
exit(1);
}
-static int
-multirotor_pos_control_thread_main(int argc, char *argv[])
+static float scale_control(float ctl, float end, float dz)
+{
+ if (ctl > dz) {
+ return (ctl - dz) / (end - dz);
+
+ } else if (ctl < -dz) {
+ return (ctl + dz) / (end - dz);
+
+ } else {
+ return 0.0f;
+ }
+}
+
+static float norm(float x, float y)
+{
+ return sqrtf(x * x + y * y);
+}
+
+static int multirotor_pos_control_thread_main(int argc, char *argv[])
{
/* welcome user */
- printf("[multirotor pos control] Control started, taking over position control\n");
+ warnx("started");
+ static int mavlink_fd;
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(mavlink_fd, "[mpc] started");
/* structures */
- struct vehicle_status_s state;
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
struct vehicle_attitude_s att;
- //struct vehicle_global_position_setpoint_s global_pos_sp;
- struct vehicle_local_position_setpoint_s local_pos_sp;
- struct vehicle_vicon_position_s local_pos;
- struct manual_control_setpoint_s manual;
+ memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
+ memset(&att_sp, 0, sizeof(att_sp));
+ struct manual_control_setpoint_s manual;
+ memset(&manual, 0, sizeof(manual));
+ struct vehicle_local_position_s local_pos;
+ memset(&local_pos, 0, sizeof(local_pos));
+ struct vehicle_local_position_setpoint_s local_pos_sp;
+ memset(&local_pos_sp, 0, sizeof(local_pos_sp));
+ struct vehicle_global_position_setpoint_s global_pos_sp;
+ memset(&global_pos_sp, 0, sizeof(global_pos_sp));
+ struct vehicle_global_velocity_setpoint_s global_vel_sp;
+ memset(&global_vel_sp, 0, sizeof(global_vel_sp));
/* subscribe to attitude, motor setpoints and system state */
+ int param_sub = orb_subscribe(ORB_ID(parameter_update));
+ int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int state_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int local_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
- //int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ int local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
+ int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
- /* publish attitude setpoint */
+ /* publish setpoint */
+ orb_advert_t local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &local_pos_sp);
+ orb_advert_t global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &global_vel_sp);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
+ bool reset_mission_sp = false;
+ bool global_pos_sp_valid = false;
+ bool reset_man_sp_z = true;
+ bool reset_man_sp_xy = true;
+ bool reset_int_z = true;
+ bool reset_int_z_manual = false;
+ bool reset_int_xy = true;
+ bool was_armed = false;
+ bool reset_auto_sp_xy = true;
+ bool reset_auto_sp_z = true;
+ bool reset_takeoff_sp = true;
+
+ hrt_abstime t_prev = 0;
+ const float alt_ctl_dz = 0.2f;
+ const float pos_ctl_dz = 0.05f;
+
+ float ref_alt = 0.0f;
+ hrt_abstime ref_alt_t = 0;
+ uint64_t local_ref_timestamp = 0;
+
+ PID_t xy_pos_pids[2];
+ PID_t xy_vel_pids[2];
+ PID_t z_pos_pid;
+ thrust_pid_t z_vel_pid;
+
thread_running = true;
- int loopcounter = 0;
-
- struct multirotor_position_control_params p;
- struct multirotor_position_control_param_handles h;
- parameters_init(&h);
- parameters_update(&h, &p);
-
-
- while (1) {
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
- /* get a local copy of local position */
- orb_copy(ORB_ID(vehicle_vicon_position), local_pos_sub, &local_pos);
- /* get a local copy of local position setpoint */
- orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp);
-
- if (loopcounter == 500) {
- parameters_update(&h, &p);
- loopcounter = 0;
+ struct multirotor_position_control_params params;
+ struct multirotor_position_control_param_handles params_h;
+ parameters_init(&params_h);
+ parameters_update(&params_h, &params);
+
+
+ for (int i = 0; i < 2; i++) {
+ pid_init(&(xy_pos_pids[i]), params.xy_p, 0.0f, params.xy_d, 1.0f, 0.0f, PID_MODE_DERIVATIV_SET, 0.02f);
+ pid_init(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, 1.0f, params.tilt_max, PID_MODE_DERIVATIV_CALC_NO_SP, 0.02f);
+ }
+
+ pid_init(&z_pos_pid, params.z_p, 0.0f, params.z_d, 1.0f, params.z_vel_max, PID_MODE_DERIVATIV_SET, 0.02f);
+ thrust_pid_init(&z_vel_pid, params.z_vel_p, params.z_vel_i, params.z_vel_d, -params.thr_max, -params.thr_min, PID_MODE_DERIVATIV_CALC_NO_SP, 0.02f);
+
+ while (!thread_should_exit) {
+
+ bool param_updated;
+ orb_check(param_sub, &param_updated);
+
+ if (param_updated) {
+ /* clear updated flag */
+ struct parameter_update_s ps;
+ orb_copy(ORB_ID(parameter_update), param_sub, &ps);
+ /* update params */
+ parameters_update(&params_h, &params);
+
+ for (int i = 0; i < 2; i++) {
+ pid_set_parameters(&(xy_pos_pids[i]), params.xy_p, 0.0f, params.xy_d, 1.0f, 0.0f);
+ /* use integral_limit_out = tilt_max / 2 */
+ float i_limit;
+
+ if (params.xy_vel_i > 0.0f) {
+ i_limit = params.tilt_max / params.xy_vel_i / 2.0f;
+
+ } else {
+ i_limit = 0.0f; // not used
+ }
+
+ pid_set_parameters(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, i_limit, params.tilt_max);
+ }
+
+ pid_set_parameters(&z_pos_pid, params.z_p, 0.0f, params.z_d, 1.0f, params.z_vel_max);
+ thrust_pid_set_parameters(&z_vel_pid, params.z_vel_p, params.z_vel_i, params.z_vel_d, -params.thr_max, -params.thr_min);
+ }
+
+ bool updated;
+
+ orb_check(control_mode_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
+ }
+
+ orb_check(global_pos_sp_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp);
+ global_pos_sp_valid = true;
+ reset_mission_sp = true;
}
- // if (state.state_machine == SYSTEM_STATE_AUTO) {
-
- // XXX IMPLEMENT POSITION CONTROL HERE
-
- float dT = 1.0f / 50.0f;
-
- float x_setpoint = 0.0f;
-
- // XXX enable switching between Vicon and local position estimate
- /* local pos is the Vicon position */
-
- // XXX just an example, lacks rotation around world-body transformation
- att_sp.pitch_body = (local_pos.x - x_setpoint) * p.p;
- att_sp.roll_body = 0.0f;
- att_sp.yaw_body = 0.0f;
- att_sp.thrust = 0.3f;
- att_sp.timestamp = hrt_absolute_time();
-
- /* publish new attitude setpoint */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- // } else if (state.state_machine == SYSTEM_STATE_STABILIZED) {
- /* set setpoint to current position */
- // XXX select pos reset channel on remote
- /* reset setpoint to current position (position hold) */
- // if (1 == 2) {
- // local_pos_sp.x = local_pos.x;
- // local_pos_sp.y = local_pos.y;
- // local_pos_sp.z = local_pos.z;
- // local_pos_sp.yaw = att.yaw;
- // }
- // }
+ hrt_abstime t = hrt_absolute_time();
+ float dt;
+
+ if (t_prev != 0) {
+ dt = (t - t_prev) * 0.000001f;
+
+ } else {
+ dt = 0.0f;
+ }
+
+ if (control_mode.flag_armed && !was_armed) {
+ /* reset setpoints and integrals on arming */
+ reset_man_sp_z = true;
+ reset_man_sp_xy = true;
+ reset_auto_sp_z = true;
+ reset_auto_sp_xy = true;
+ reset_takeoff_sp = true;
+ reset_int_z = true;
+ reset_int_xy = true;
+ }
+
+ was_armed = control_mode.flag_armed;
+
+ t_prev = t;
+
+ if (control_mode.flag_control_altitude_enabled || control_mode.flag_control_velocity_enabled || control_mode.flag_control_position_enabled) {
+ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
+ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
+ orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
+
+ float z_sp_offs_max = params.z_vel_max / params.z_p * 2.0f;
+ float xy_sp_offs_max = params.xy_vel_max / params.xy_p * 2.0f;
+ float sp_move_rate[3] = { 0.0f, 0.0f, 0.0f };
+
+ if (control_mode.flag_control_manual_enabled) {
+ /* manual control */
+ /* check for reference point updates and correct setpoint */
+ if (local_pos.ref_timestamp != ref_alt_t) {
+ if (ref_alt_t != 0) {
+ /* home alt changed, don't follow large ground level changes in manual flight */
+ local_pos_sp.z += local_pos.ref_alt - ref_alt;
+ }
+
+ ref_alt_t = local_pos.ref_timestamp;
+ ref_alt = local_pos.ref_alt;
+ // TODO also correct XY setpoint
+ }
+
+ /* reset setpoints to current position if needed */
+ if (control_mode.flag_control_altitude_enabled) {
+ if (reset_man_sp_z) {
+ reset_man_sp_z = false;
+ local_pos_sp.z = local_pos.z;
+ mavlink_log_info(mavlink_fd, "[mpc] reset alt sp: %.2f", (double) - local_pos_sp.z);
+ }
+
+ /* move altitude setpoint with throttle stick */
+ float z_sp_ctl = scale_control(manual.throttle - 0.5f, 0.5f, alt_ctl_dz);
+
+ if (z_sp_ctl != 0.0f) {
+ sp_move_rate[2] = -z_sp_ctl * params.z_vel_max;
+ local_pos_sp.z += sp_move_rate[2] * dt;
+
+ if (local_pos_sp.z > local_pos.z + z_sp_offs_max) {
+ local_pos_sp.z = local_pos.z + z_sp_offs_max;
+
+ } else if (local_pos_sp.z < local_pos.z - z_sp_offs_max) {
+ local_pos_sp.z = local_pos.z - z_sp_offs_max;
+ }
+ }
+ }
+
+ if (control_mode.flag_control_position_enabled) {
+ if (reset_man_sp_xy) {
+ reset_man_sp_xy = false;
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ pid_reset_integral(&xy_vel_pids[0]);
+ pid_reset_integral(&xy_vel_pids[1]);
+ mavlink_log_info(mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
+ }
+
+ /* move position setpoint with roll/pitch stick */
+ float pos_pitch_sp_ctl = scale_control(-manual.pitch / params.rc_scale_pitch, 1.0f, pos_ctl_dz);
+ float pos_roll_sp_ctl = scale_control(manual.roll / params.rc_scale_roll, 1.0f, pos_ctl_dz);
+
+ if (pos_pitch_sp_ctl != 0.0f || pos_roll_sp_ctl != 0.0f) {
+ /* calculate direction and increment of control in NED frame */
+ float xy_sp_ctl_dir = att.yaw + atan2f(pos_roll_sp_ctl, pos_pitch_sp_ctl);
+ float xy_sp_ctl_speed = norm(pos_pitch_sp_ctl, pos_roll_sp_ctl) * params.xy_vel_max;
+ sp_move_rate[0] = cosf(xy_sp_ctl_dir) * xy_sp_ctl_speed;
+ sp_move_rate[1] = sinf(xy_sp_ctl_dir) * xy_sp_ctl_speed;
+ local_pos_sp.x += sp_move_rate[0] * dt;
+ local_pos_sp.y += sp_move_rate[1] * dt;
+ /* limit maximum setpoint from position offset and preserve direction
+ * fail safe, should not happen in normal operation */
+ float pos_vec_x = local_pos_sp.x - local_pos.x;
+ float pos_vec_y = local_pos_sp.y - local_pos.y;
+ float pos_vec_norm = norm(pos_vec_x, pos_vec_y) / xy_sp_offs_max;
+
+ if (pos_vec_norm > 1.0f) {
+ local_pos_sp.x = local_pos.x + pos_vec_x / pos_vec_norm;
+ local_pos_sp.y = local_pos.y + pos_vec_y / pos_vec_norm;
+ }
+ }
+ }
+
+ /* copy yaw setpoint to vehicle_local_position_setpoint topic */
+ local_pos_sp.yaw = att_sp.yaw_body;
+
+ /* local position setpoint is valid and can be used for auto loiter after position controlled mode */
+ reset_auto_sp_xy = !control_mode.flag_control_position_enabled;
+ reset_auto_sp_z = !control_mode.flag_control_altitude_enabled;
+ reset_takeoff_sp = true;
+
+ /* force reprojection of global setpoint after manual mode */
+ reset_mission_sp = true;
+
+ } else if (control_mode.flag_control_auto_enabled) {
+ /* AUTO mode, use global setpoint */
+ if (control_mode.auto_state == NAVIGATION_STATE_AUTO_READY) {
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
+
+ } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+ if (reset_takeoff_sp) {
+ reset_takeoff_sp = false;
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ local_pos_sp.z = - params.takeoff_alt - params.takeoff_gap;
+ att_sp.yaw_body = att.yaw;
+ mavlink_log_info(mavlink_fd, "[mpc] takeoff sp: %.2f %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y, (double) - local_pos_sp.z);
+ }
+
+ reset_auto_sp_xy = false;
+ reset_auto_sp_z = true;
+
+ } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_RTL) {
+ // TODO
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
+
+ } else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_MISSION) {
+ /* init local projection using local position ref */
+ if (local_pos.ref_timestamp != local_ref_timestamp) {
+ reset_mission_sp = true;
+ local_ref_timestamp = local_pos.ref_timestamp;
+ double lat_home = local_pos.ref_lat * 1e-7;
+ double lon_home = local_pos.ref_lon * 1e-7;
+ map_projection_init(lat_home, lon_home);
+ mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", (double)lat_home, (double)lon_home);
+ }
+
+ if (reset_mission_sp) {
+ reset_mission_sp = false;
+ /* update global setpoint projection */
+
+ if (global_pos_sp_valid) {
+ /* global position setpoint valid, use it */
+ double sp_lat = global_pos_sp.lat * 1e-7;
+ double sp_lon = global_pos_sp.lon * 1e-7;
+ /* project global setpoint to local setpoint */
+ map_projection_project(sp_lat, sp_lon, &(local_pos_sp.x), &(local_pos_sp.y));
+
+ if (global_pos_sp.altitude_is_relative) {
+ local_pos_sp.z = -global_pos_sp.altitude;
+
+ } else {
+ local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude;
+ }
+ /* update yaw setpoint only if value is valid */
+ if (isfinite(global_pos_sp.yaw) && fabsf(global_pos_sp.yaw) < M_TWOPI) {
+ att_sp.yaw_body = global_pos_sp.yaw;
+ }
+
+ mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", (double)sp_lat, sp_lon, (double)local_pos_sp.x, (double)local_pos_sp.y);
+
+ } else {
+ if (reset_auto_sp_xy) {
+ reset_auto_sp_xy = false;
+ /* local position setpoint is invalid,
+ * use current position as setpoint for loiter */
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ local_pos_sp.yaw = att.yaw;
+ }
+
+ if (reset_auto_sp_z) {
+ reset_auto_sp_z = false;
+ local_pos_sp.z = local_pos.z;
+ }
+
+ mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
+ }
+ }
+
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
+ }
+
+ if (control_mode.auto_state != NAVIGATION_STATE_AUTO_TAKEOFF) {
+ reset_takeoff_sp = true;
+ }
+
+ if (control_mode.auto_state != NAVIGATION_STATE_AUTO_MISSION) {
+ reset_mission_sp = true;
+ }
+
+ /* copy yaw setpoint to vehicle_local_position_setpoint topic */
+ local_pos_sp.yaw = att_sp.yaw_body;
+
+ /* reset setpoints after AUTO mode */
+ reset_man_sp_xy = true;
+ reset_man_sp_z = true;
+
+ } else {
+ /* no control (failsafe), loiter or stay on ground */
+ if (local_pos.landed) {
+ /* landed: move setpoint down */
+ /* in air: hold altitude */
+ if (local_pos_sp.z < 5.0f) {
+ /* set altitude setpoint to 5m under ground,
+ * don't set it too deep to avoid unexpected landing in case of false "landed" signal */
+ local_pos_sp.z = 5.0f;
+ mavlink_log_info(mavlink_fd, "[mpc] landed, set alt: %.2f", (double) - local_pos_sp.z);
+ }
+
+ reset_man_sp_z = true;
+
+ } else {
+ /* in air: hold altitude */
+ if (reset_man_sp_z) {
+ reset_man_sp_z = false;
+ local_pos_sp.z = local_pos.z;
+ mavlink_log_info(mavlink_fd, "[mpc] set loiter alt: %.2f", (double) - local_pos_sp.z);
+ }
+
+ reset_auto_sp_z = false;
+ }
+
+ if (control_mode.flag_control_position_enabled) {
+ if (reset_man_sp_xy) {
+ reset_man_sp_xy = false;
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ local_pos_sp.yaw = att.yaw;
+ att_sp.yaw_body = att.yaw;
+ mavlink_log_info(mavlink_fd, "[mpc] set loiter pos: %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
+ }
+
+ reset_auto_sp_xy = false;
+ }
+ }
+
+ /* publish local position setpoint */
+ orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
+
+ /* run position & altitude controllers, calculate velocity setpoint */
+ if (control_mode.flag_control_altitude_enabled) {
+ global_vel_sp.vz = pid_calculate(&z_pos_pid, local_pos_sp.z, local_pos.z, local_pos.vz - sp_move_rate[2], dt) + sp_move_rate[2];
+
+ } else {
+ reset_man_sp_z = true;
+ global_vel_sp.vz = 0.0f;
+ }
+
+ if (control_mode.flag_control_position_enabled) {
+ /* calculate velocity set point in NED frame */
+ global_vel_sp.vx = pid_calculate(&xy_pos_pids[0], local_pos_sp.x, local_pos.x, local_pos.vx - sp_move_rate[0], dt) + sp_move_rate[0];
+ global_vel_sp.vy = pid_calculate(&xy_pos_pids[1], local_pos_sp.y, local_pos.y, local_pos.vy - sp_move_rate[1], dt) + sp_move_rate[1];
+
+ /* limit horizontal speed */
+ float xy_vel_sp_norm = norm(global_vel_sp.vx, global_vel_sp.vy) / params.xy_vel_max;
+
+ if (xy_vel_sp_norm > 1.0f) {
+ global_vel_sp.vx /= xy_vel_sp_norm;
+ global_vel_sp.vy /= xy_vel_sp_norm;
+ }
+
+ } else {
+ reset_man_sp_xy = true;
+ global_vel_sp.vx = 0.0f;
+ global_vel_sp.vy = 0.0f;
+ }
+
+ /* publish new velocity setpoint */
+ orb_publish(ORB_ID(vehicle_global_velocity_setpoint), global_vel_sp_pub, &global_vel_sp);
+ // TODO subscribe to velocity setpoint if altitude/position control disabled
+
+ if (control_mode.flag_control_climb_rate_enabled || control_mode.flag_control_velocity_enabled) {
+ /* run velocity controllers, calculate thrust vector with attitude-thrust compensation */
+ float thrust_sp[3] = { 0.0f, 0.0f, 0.0f };
+
+ if (control_mode.flag_control_climb_rate_enabled) {
+ if (reset_int_z) {
+ reset_int_z = false;
+ float i = params.thr_min;
+
+ if (reset_int_z_manual) {
+ i = manual.throttle;
+
+ if (i < params.thr_min) {
+ i = params.thr_min;
+
+ } else if (i > params.thr_max) {
+ i = params.thr_max;
+ }
+ }
+
+ thrust_pid_set_integral(&z_vel_pid, -i);
+ mavlink_log_info(mavlink_fd, "[mpc] reset hovering thrust: %.2f", (double)i);
+ }
+
+ thrust_sp[2] = thrust_pid_calculate(&z_vel_pid, global_vel_sp.vz, local_pos.vz, dt, att.R[2][2]);
+ att_sp.thrust = -thrust_sp[2];
+
+ } else {
+ /* reset thrust integral when altitude control enabled */
+ reset_int_z = true;
+ }
+
+ if (control_mode.flag_control_velocity_enabled) {
+ /* calculate thrust set point in NED frame */
+ if (reset_int_xy) {
+ reset_int_xy = false;
+ pid_reset_integral(&xy_vel_pids[0]);
+ pid_reset_integral(&xy_vel_pids[1]);
+ mavlink_log_info(mavlink_fd, "[mpc] reset pos integral");
+ }
+
+ thrust_sp[0] = pid_calculate(&xy_vel_pids[0], global_vel_sp.vx, local_pos.vx, 0.0f, dt);
+ thrust_sp[1] = pid_calculate(&xy_vel_pids[1], global_vel_sp.vy, local_pos.vy, 0.0f, dt);
+
+ /* thrust_vector now contains desired acceleration (but not in m/s^2) in NED frame */
+ /* limit horizontal part of thrust */
+ float thrust_xy_dir = atan2f(thrust_sp[1], thrust_sp[0]);
+ /* assuming that vertical component of thrust is g,
+ * horizontal component = g * tan(alpha) */
+ float tilt = atanf(norm(thrust_sp[0], thrust_sp[1]));
+
+ if (tilt > params.tilt_max) {
+ tilt = params.tilt_max;
+ }
+
+ /* convert direction to body frame */
+ thrust_xy_dir -= att.yaw;
+ /* calculate roll and pitch */
+ att_sp.roll_body = sinf(thrust_xy_dir) * tilt;
+ att_sp.pitch_body = -cosf(thrust_xy_dir) * tilt / cosf(att_sp.roll_body);
+
+ } else {
+ reset_int_xy = true;
+ }
+
+ att_sp.timestamp = hrt_absolute_time();
+
+ /* publish new attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ }
+
+ } else {
+ /* position controller disabled, reset setpoints */
+ reset_man_sp_z = true;
+ reset_man_sp_xy = true;
+ reset_int_z = true;
+ reset_int_xy = true;
+ reset_mission_sp = true;
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
+ }
+
+ /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
+ reset_int_z_manual = control_mode.flag_armed && control_mode.flag_control_manual_enabled && !control_mode.flag_control_climb_rate_enabled;
/* run at approximately 50 Hz */
usleep(20000);
- loopcounter++;
-
}
- printf("[multirotor pos control] ending now...\n");
+ warnx("stopped");
+ mavlink_log_info(mavlink_fd, "[mpc] stopped");
thread_running = false;
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
index 6b73dc405..b7041e4d5 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
@@ -1,8 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,29 +33,80 @@
****************************************************************************/
/*
- * @file multirotor_position_control_params.c
- *
- * Parameters for EKF filter
+ * @file multirotor_pos_control_params.c
+ *
+ * Parameters for multirotor_pos_control
*/
#include "multirotor_pos_control_params.h"
-/* Extended Kalman Filter covariances */
-
/* controller parameters */
-PARAM_DEFINE_FLOAT(MC_POS_P, 0.2f);
+PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.2f);
+PARAM_DEFINE_FLOAT(MPC_THR_MAX, 0.8f);
+PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_D, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_P, 0.1f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_I, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 3.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_P, 0.5f);
+PARAM_DEFINE_FLOAT(MPC_XY_D, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_P, 0.2f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_I, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
+PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 0.5f);
int parameters_init(struct multirotor_position_control_param_handles *h)
{
- /* PID parameters */
- h->p = param_find("MC_POS_P");
+ h->takeoff_alt = param_find("NAV_TAKEOFF_ALT");
+ h->takeoff_gap = param_find("NAV_TAKEOFF_GAP");
+ h->thr_min = param_find("MPC_THR_MIN");
+ h->thr_max = param_find("MPC_THR_MAX");
+ h->z_p = param_find("MPC_Z_P");
+ h->z_d = param_find("MPC_Z_D");
+ h->z_vel_p = param_find("MPC_Z_VEL_P");
+ h->z_vel_i = param_find("MPC_Z_VEL_I");
+ h->z_vel_d = param_find("MPC_Z_VEL_D");
+ h->z_vel_max = param_find("MPC_Z_VEL_MAX");
+ h->xy_p = param_find("MPC_XY_P");
+ h->xy_d = param_find("MPC_XY_D");
+ h->xy_vel_p = param_find("MPC_XY_VEL_P");
+ h->xy_vel_i = param_find("MPC_XY_VEL_I");
+ h->xy_vel_d = param_find("MPC_XY_VEL_D");
+ h->xy_vel_max = param_find("MPC_XY_VEL_MAX");
+ h->tilt_max = param_find("MPC_TILT_MAX");
+
+ h->rc_scale_pitch = param_find("RC_SCALE_PITCH");
+ h->rc_scale_roll = param_find("RC_SCALE_ROLL");
+ h->rc_scale_yaw = param_find("RC_SCALE_YAW");
return OK;
}
int parameters_update(const struct multirotor_position_control_param_handles *h, struct multirotor_position_control_params *p)
{
- param_get(h->p, &(p->p));
+ param_get(h->takeoff_alt, &(p->takeoff_alt));
+ param_get(h->takeoff_gap, &(p->takeoff_gap));
+ param_get(h->thr_min, &(p->thr_min));
+ param_get(h->thr_max, &(p->thr_max));
+ param_get(h->z_p, &(p->z_p));
+ param_get(h->z_d, &(p->z_d));
+ param_get(h->z_vel_p, &(p->z_vel_p));
+ param_get(h->z_vel_i, &(p->z_vel_i));
+ param_get(h->z_vel_d, &(p->z_vel_d));
+ param_get(h->z_vel_max, &(p->z_vel_max));
+ param_get(h->xy_p, &(p->xy_p));
+ param_get(h->xy_d, &(p->xy_d));
+ param_get(h->xy_vel_p, &(p->xy_vel_p));
+ param_get(h->xy_vel_i, &(p->xy_vel_i));
+ param_get(h->xy_vel_d, &(p->xy_vel_d));
+ param_get(h->xy_vel_max, &(p->xy_vel_max));
+ param_get(h->tilt_max, &(p->tilt_max));
+
+ param_get(h->rc_scale_pitch, &(p->rc_scale_pitch));
+ param_get(h->rc_scale_roll, &(p->rc_scale_roll));
+ param_get(h->rc_scale_yaw, &(p->rc_scale_yaw));
return OK;
}
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control_params.h b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
index 274f6c22a..fc658dadb 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
@@ -1,8 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,23 +33,59 @@
****************************************************************************/
/*
- * @file multirotor_position_control_params.h
- *
- * Parameters for position controller
+ * @file multirotor_pos_control_params.h
+ *
+ * Parameters for multirotor_pos_control
*/
#include <systemlib/param/param.h>
struct multirotor_position_control_params {
- float p;
- float i;
- float d;
+ float takeoff_alt;
+ float takeoff_gap;
+ float thr_min;
+ float thr_max;
+ float z_p;
+ float z_d;
+ float z_vel_p;
+ float z_vel_i;
+ float z_vel_d;
+ float z_vel_max;
+ float xy_p;
+ float xy_d;
+ float xy_vel_p;
+ float xy_vel_i;
+ float xy_vel_d;
+ float xy_vel_max;
+ float tilt_max;
+
+ float rc_scale_pitch;
+ float rc_scale_roll;
+ float rc_scale_yaw;
};
struct multirotor_position_control_param_handles {
- param_t p;
- param_t i;
- param_t d;
+ param_t takeoff_alt;
+ param_t takeoff_gap;
+ param_t thr_min;
+ param_t thr_max;
+ param_t z_p;
+ param_t z_d;
+ param_t z_vel_p;
+ param_t z_vel_i;
+ param_t z_vel_d;
+ param_t z_vel_max;
+ param_t xy_p;
+ param_t xy_d;
+ param_t xy_vel_p;
+ param_t xy_vel_i;
+ param_t xy_vel_d;
+ param_t xy_vel_max;
+ param_t tilt_max;
+
+ param_t rc_scale_pitch;
+ param_t rc_scale_roll;
+ param_t rc_scale_yaw;
};
/**
diff --git a/src/modules/multirotor_pos_control/position_control.c b/src/modules/multirotor_pos_control/position_control.c
deleted file mode 100644
index 9c53a5bf6..000000000
--- a/src/modules/multirotor_pos_control/position_control.c
+++ /dev/null
@@ -1,235 +0,0 @@
-// /****************************************************************************
-// *
-// * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
-// * Author: @author Lorenz Meier <lm@inf.ethz.ch>
-// * @author Laurens Mackay <mackayl@student.ethz.ch>
-// * @author Tobias Naegeli <naegelit@student.ethz.ch>
-// * @author Martin Rutschmann <rutmarti@student.ethz.ch>
-// *
-// * 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_position_control.c
-// * Implementation of the position control for a multirotor VTOL
-// */
-
-// #include <stdio.h>
-// #include <stdlib.h>
-// #include <stdio.h>
-// #include <stdint.h>
-// #include <math.h>
-// #include <stdbool.h>
-// #include <float.h>
-// #include <systemlib/pid/pid.h>
-
-// #include "multirotor_position_control.h"
-
-// void control_multirotor_position(const struct vehicle_state_s *vstatus, const struct vehicle_manual_control_s *manual,
-// const struct vehicle_attitude_s *att, const struct vehicle_local_position_s *local_pos,
-// const struct vehicle_local_position_setpoint_s *local_pos_sp, struct vehicle_attitude_setpoint_s *att_sp)
-// {
-// static PID_t distance_controller;
-
-// static int read_ret;
-// static global_data_position_t position_estimated;
-
-// static uint16_t counter;
-
-// static bool initialized;
-// static uint16_t pm_counter;
-
-// static float lat_next;
-// static float lon_next;
-
-// static float pitch_current;
-
-// static float thrust_total;
-
-
-// if (initialized == false) {
-
-// pid_init(&distance_controller,
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_P],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_I],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_D],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_AWU],
-// PID_MODE_DERIVATIV_CALC, 150);//150
-
-// // pid_pos_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_LIM];
-// // pid_pos_z_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_Z_LIM];
-
-// thrust_total = 0.0f;
-
-// /* Position initialization */
-// /* Wait for new position estimate */
-// do {
-// read_ret = read_lock_position(&position_estimated);
-// } while (read_ret != 0);
-
-// lat_next = position_estimated.lat;
-// lon_next = position_estimated.lon;
-
-// /* attitude initialization */
-// global_data_lock(&global_data_attitude->access_conf);
-// pitch_current = global_data_attitude->pitch;
-// global_data_unlock(&global_data_attitude->access_conf);
-
-// initialized = true;
-// }
-
-// /* load new parameters with 10Hz */
-// if (counter % 50 == 0) {
-// if (global_data_trylock(&global_data_parameter_storage->access_conf) == 0) {
-// /* check whether new parameters are available */
-// if (global_data_parameter_storage->counter > pm_counter) {
-// pid_set_parameters(&distance_controller,
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_P],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_I],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_D],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_AWU]);
-
-// //
-// // pid_pos_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_LIM];
-// // pid_pos_z_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_Z_LIM];
-
-// pm_counter = global_data_parameter_storage->counter;
-// printf("Position controller changed pid parameters\n");
-// }
-// }
-
-// global_data_unlock(&global_data_parameter_storage->access_conf);
-// }
-
-
-// /* Wait for new position estimate */
-// do {
-// read_ret = read_lock_position(&position_estimated);
-// } while (read_ret != 0);
-
-// /* Get next waypoint */ //TODO: add local copy
-
-// if (0 == global_data_trylock(&global_data_position_setpoint->access_conf)) {
-// lat_next = global_data_position_setpoint->x;
-// lon_next = global_data_position_setpoint->y;
-// global_data_unlock(&global_data_position_setpoint->access_conf);
-// }
-
-// /* Get distance to waypoint */
-// float distance_to_waypoint = get_distance_to_next_waypoint(position_estimated.lat , position_estimated.lon, lat_next, lon_next);
-// // if(counter % 5 == 0)
-// // printf("distance_to_waypoint: %.4f\n", distance_to_waypoint);
-
-// /* Get bearing to waypoint (direction on earth surface to next waypoint) */
-// float bearing = get_bearing_to_next_waypoint(position_estimated.lat, position_estimated.lon, lat_next, lon_next);
-
-// if (counter % 5 == 0)
-// printf("bearing: %.4f\n", bearing);
-
-// /* Calculate speed in direction of bearing (needed for controller) */
-// float speed_norm = sqrtf(position_estimated.vx * position_estimated.vx + position_estimated.vy * position_estimated.vy);
-// // if(counter % 5 == 0)
-// // printf("speed_norm: %.4f\n", speed_norm);
-// float speed_to_waypoint = 0; //(position_estimated.vx * cosf(bearing) + position_estimated.vy * sinf(bearing))/speed_norm; //FIXME, TODO: re-enable this once we have a full estimate of the speed, then we can do a PID for the distance controller
-
-// /* Control Thrust in bearing direction */
-// float horizontal_thrust = -pid_calculate(&distance_controller, 0, distance_to_waypoint, speed_to_waypoint,
-// CONTROL_PID_POSITION_INTERVAL); //TODO: maybe this "-" sign is an error somewhere else
-
-// // if(counter % 5 == 0)
-// // printf("horizontal thrust: %.4f\n", horizontal_thrust);
-
-// /* Get total thrust (from remote for now) */
-// if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
-// thrust_total = (float)global_data_rc_channels->chan[THROTTLE].scale; //TODO: how should we use the RC_CHANNELS_FUNCTION enum?
-// global_data_unlock(&global_data_rc_channels->access_conf);
-// }
-
-// const float max_gas = 500.0f;
-// thrust_total *= max_gas / 20000.0f; //TODO: check this
-// thrust_total += max_gas / 2.0f;
-
-
-// if (horizontal_thrust > thrust_total) {
-// horizontal_thrust = thrust_total;
-
-// } else if (horizontal_thrust < -thrust_total) {
-// horizontal_thrust = -thrust_total;
-// }
-
-
-
-// //TODO: maybe we want to add a speed controller later...
-
-// /* Calclulate thrust in east and north direction */
-// float thrust_north = cosf(bearing) * horizontal_thrust;
-// float thrust_east = sinf(bearing) * horizontal_thrust;
-
-// if (counter % 10 == 0) {
-// printf("thrust north: %.4f\n", thrust_north);
-// printf("thrust east: %.4f\n", thrust_east);
-// fflush(stdout);
-// }
-
-// /* Get current attitude */
-// if (0 == global_data_trylock(&global_data_attitude->access_conf)) {
-// pitch_current = global_data_attitude->pitch;
-// global_data_unlock(&global_data_attitude->access_conf);
-// }
-
-// /* Get desired pitch & roll */
-// float pitch_desired = 0.0f;
-// float roll_desired = 0.0f;
-
-// if (thrust_total != 0) {
-// float pitch_fraction = -thrust_north / thrust_total;
-// float roll_fraction = thrust_east / (cosf(pitch_current) * thrust_total);
-
-// if (roll_fraction < -1) {
-// roll_fraction = -1;
-
-// } else if (roll_fraction > 1) {
-// roll_fraction = 1;
-// }
-
-// // if(counter % 5 == 0)
-// // {
-// // printf("pitch_fraction: %.4f, roll_fraction: %.4f\n",pitch_fraction, roll_fraction);
-// // fflush(stdout);
-// // }
-
-// pitch_desired = asinf(pitch_fraction);
-// roll_desired = asinf(roll_fraction);
-// }
-
-// att_sp.roll = roll_desired;
-// att_sp.pitch = pitch_desired;
-
-// counter++;
-// }
diff --git a/src/modules/multirotor_pos_control/thrust_pid.c b/src/modules/multirotor_pos_control/thrust_pid.c
new file mode 100644
index 000000000..b985630ae
--- /dev/null
+++ b/src/modules/multirotor_pos_control/thrust_pid.c
@@ -0,0 +1,189 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 thrust_pid.c
+ *
+ * Implementation of thrust control PID.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include "thrust_pid.h"
+#include <math.h>
+
+__EXPORT void thrust_pid_init(thrust_pid_t *pid, float kp, float ki, float kd, float limit_min, float limit_max, uint8_t mode, float dt_min)
+{
+ pid->kp = kp;
+ pid->ki = ki;
+ pid->kd = kd;
+ pid->limit_min = limit_min;
+ pid->limit_max = limit_max;
+ pid->mode = mode;
+ pid->dt_min = dt_min;
+ pid->last_output = 0.0f;
+ pid->sp = 0.0f;
+ pid->error_previous = 0.0f;
+ pid->integral = 0.0f;
+}
+
+__EXPORT int thrust_pid_set_parameters(thrust_pid_t *pid, float kp, float ki, float kd, float limit_min, float limit_max)
+{
+ int ret = 0;
+
+ if (isfinite(kp)) {
+ pid->kp = kp;
+
+ } else {
+ ret = 1;
+ }
+
+ if (isfinite(ki)) {
+ pid->ki = ki;
+
+ } else {
+ ret = 1;
+ }
+
+ if (isfinite(kd)) {
+ pid->kd = kd;
+
+ } else {
+ ret = 1;
+ }
+
+ if (isfinite(limit_min)) {
+ pid->limit_min = limit_min;
+
+ } else {
+ ret = 1;
+ }
+
+ if (isfinite(limit_max)) {
+ pid->limit_max = limit_max;
+
+ } else {
+ ret = 1;
+ }
+
+ return ret;
+}
+
+__EXPORT float thrust_pid_calculate(thrust_pid_t *pid, float sp, float val, float dt, float r22)
+{
+ /* Alternative integral component calculation
+ *
+ * start:
+ * error = setpoint - current_value
+ * integral = integral + (Ki * error * dt)
+ * derivative = (error - previous_error) / dt
+ * previous_error = error
+ * output = (Kp * error) + integral + (Kd * derivative)
+ * wait(dt)
+ * goto start
+ */
+
+ if (!isfinite(sp) || !isfinite(val) || !isfinite(dt)) {
+ return pid->last_output;
+ }
+
+ float i, d;
+ pid->sp = sp;
+
+ // Calculated current error value
+ float error = pid->sp - val;
+
+ // Calculate or measured current error derivative
+ if (pid->mode == THRUST_PID_MODE_DERIVATIV_CALC) {
+ d = (error - pid->error_previous) / fmaxf(dt, pid->dt_min);
+ pid->error_previous = error;
+
+ } else if (pid->mode == THRUST_PID_MODE_DERIVATIV_CALC_NO_SP) {
+ d = (-val - pid->error_previous) / fmaxf(dt, pid->dt_min);
+ pid->error_previous = -val;
+
+ } else {
+ d = 0.0f;
+ }
+
+ if (!isfinite(d)) {
+ d = 0.0f;
+ }
+
+ /* calculate the error integral */
+ i = pid->integral + (pid->ki * error * dt);
+
+ /* attitude-thrust compensation
+ * r22 is (2, 2) componet of rotation matrix for current attitude */
+ float att_comp;
+
+ if (r22 > 0.8f)
+ att_comp = 1.0f / r22;
+ else if (r22 > 0.0f)
+ att_comp = ((1.0f / 0.8f - 1.0f) / 0.8f) * r22 + 1.0f;
+ else
+ att_comp = 1.0f;
+
+ /* calculate output */
+ float output = ((error * pid->kp) + i + (d * pid->kd)) * att_comp;
+
+ /* check for saturation */
+ if (output < pid->limit_min || output > pid->limit_max) {
+ /* saturated, recalculate output with old integral */
+ output = (error * pid->kp) + pid->integral + (d * pid->kd);
+
+ } else {
+ if (isfinite(i)) {
+ pid->integral = i;
+ }
+ }
+
+ if (isfinite(output)) {
+ if (output > pid->limit_max) {
+ output = pid->limit_max;
+
+ } else if (output < pid->limit_min) {
+ output = pid->limit_min;
+ }
+
+ pid->last_output = output;
+ }
+
+ return pid->last_output;
+}
+
+__EXPORT void thrust_pid_set_integral(thrust_pid_t *pid, float i)
+{
+ pid->integral = i;
+}
diff --git a/src/modules/mathlib/math/Quaternion.hpp b/src/modules/multirotor_pos_control/thrust_pid.h
index 4b4e959d8..5e169c1ba 100644
--- a/src/modules/mathlib/math/Quaternion.hpp
+++ b/src/modules/multirotor_pos_control/thrust_pid.h
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,84 +33,44 @@
****************************************************************************/
/**
- * @file Quaternion.hpp
+ * @file thrust_pid.h
*
- * math quaternion lib
+ * Definition of thrust control PID interface.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
-//#pragma once
-
-#include "Vector.hpp"
-#include "Matrix.hpp"
-
-namespace math
-{
-
-class Dcm;
-class EulerAngles;
-
-class __EXPORT Quaternion : public Vector
-{
-public:
-
- /**
- * default ctor
- */
- Quaternion();
-
- /**
- * ctor from floats
- */
- Quaternion(float a, float b, float c, float d);
-
- /**
- * ctor from data
- */
- Quaternion(const float *data);
-
- /**
- * ctor from Vector
- */
- Quaternion(const Vector &v);
-
- /**
- * ctor from EulerAngles
- */
- Quaternion(const EulerAngles &euler);
+#ifndef THRUST_PID_H_
+#define THRUST_PID_H_
- /**
- * ctor from Dcm
- */
- Quaternion(const Dcm &dcm);
+#include <stdint.h>
- /**
- * deep copy ctor
- */
- Quaternion(const Quaternion &right);
+__BEGIN_DECLS
- /**
- * dtor
- */
- virtual ~Quaternion();
+/* PID_MODE_DERIVATIV_CALC calculates discrete derivative from previous error */
+#define THRUST_PID_MODE_DERIVATIV_CALC 0
+/* PID_MODE_DERIVATIV_CALC_NO_SP calculates discrete derivative from previous value, setpoint derivative is ignored */
+#define THRUST_PID_MODE_DERIVATIV_CALC_NO_SP 1
- /**
- * derivative
- */
- Vector derivative(const Vector &w);
+typedef struct {
+ float kp;
+ float ki;
+ float kd;
+ float sp;
+ float integral;
+ float error_previous;
+ float last_output;
+ float limit_min;
+ float limit_max;
+ float dt_min;
+ uint8_t mode;
+} thrust_pid_t;
- /**
- * accessors
- */
- void setA(float a) { (*this)(0) = a; }
- void setB(float b) { (*this)(1) = b; }
- void setC(float c) { (*this)(2) = c; }
- void setD(float d) { (*this)(3) = d; }
- const float &getA() const { return (*this)(0); }
- const float &getB() const { return (*this)(1); }
- const float &getC() const { return (*this)(2); }
- const float &getD() const { return (*this)(3); }
-};
+__EXPORT void thrust_pid_init(thrust_pid_t *pid, float kp, float ki, float kd, float limit_min, float limit_max, uint8_t mode, float dt_min);
+__EXPORT int thrust_pid_set_parameters(thrust_pid_t *pid, float kp, float ki, float kd, float limit_min, float limit_max);
+__EXPORT float thrust_pid_calculate(thrust_pid_t *pid, float sp, float val, float dt, float r22);
+__EXPORT void thrust_pid_set_integral(thrust_pid_t *pid, float i);
-int __EXPORT quaternionTest();
-} // math
+__END_DECLS
+#endif /* THRUST_PID_H_ */
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
new file mode 100644
index 000000000..0404b06c7
--- /dev/null
+++ b/src/modules/navigator/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Main Navigation Controller
+#
+
+MODULE_COMMAND = navigator
+
+SRCS = navigator_main.cpp \
+ navigator_params.c
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
new file mode 100644
index 000000000..f6c44444a
--- /dev/null
+++ b/src/modules/navigator/navigator_main.cpp
@@ -0,0 +1,604 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier
+ *
+ * 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 navigator_main.c
+ * Implementation of the main navigation state machine.
+ *
+ * Handles missions, geo fencing and failsafe navigation behavior.
+ */
+
+#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 <drivers/drv_hrt.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/mission.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+
+/**
+ * navigator app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
+
+class Navigator
+{
+public:
+ /**
+ * Constructor
+ */
+ Navigator();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~Navigator();
+
+ /**
+ * Start the sensors task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _navigator_task; /**< task handle for sensor task */
+
+ int _global_pos_sub;
+ int _att_sub; /**< vehicle attitude subscription */
+ int _attitude_sub; /**< raw rc channels data subscription */
+ int _airspeed_sub; /**< airspeed subscription */
+ int _vstatus_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_control_sub; /**< notification of manual control updates */
+ int _mission_sub;
+
+ orb_advert_t _triplet_pub; /**< position setpoint */
+
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
+ struct manual_control_setpoint_s _manual; /**< r/c channel data */
+ struct airspeed_s _airspeed; /**< airspeed */
+ struct vehicle_status_s _vstatus; /**< vehicle status */
+ struct vehicle_global_position_s _global_pos; /**< global vehicle position */
+ struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ unsigned _mission_items_maxcount; /**< maximum number of mission items supported */
+ struct mission_item_s * _mission_items; /**< storage for mission items */
+ bool _mission_valid; /**< flag if mission is valid */
+
+ /** manual control states */
+ float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
+ float _loiter_hold_lat;
+ float _loiter_hold_lon;
+ float _loiter_hold_alt;
+ bool _loiter_hold;
+
+ struct {
+ float throttle_cruise;
+ } _parameters; /**< local copies of interesting parameters */
+
+ struct {
+ param_t throttle_cruise;
+
+ } _parameter_handles; /**< handles for interesting parameters */
+
+
+ /**
+ * Update our local parameter cache.
+ */
+ int parameters_update();
+
+ /**
+ * Update control outputs
+ *
+ */
+ void control_update();
+
+ /**
+ * Check for changes in vehicle status.
+ */
+ void vehicle_status_poll();
+
+ /**
+ * Check for position updates.
+ */
+ void vehicle_attitude_poll();
+
+ /**
+ * Check for set triplet updates.
+ */
+ void mission_poll();
+
+ /**
+ * Control throttle.
+ */
+ float control_throttle(float energy_error);
+
+ /**
+ * Control pitch.
+ */
+ float control_pitch(float altitude_error);
+
+ void calculate_airspeed_errors();
+ void calculate_gndspeed_undershoot();
+ void calculate_altitude_error();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main sensor collection task.
+ */
+ void task_main() __attribute__((noreturn));
+};
+
+namespace navigator
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+Navigator *g_navigator;
+}
+
+Navigator::Navigator() :
+
+ _task_should_exit(false),
+ _navigator_task(-1),
+
+/* subscriptions */
+ _global_pos_sub(-1),
+ _att_sub(-1),
+ _airspeed_sub(-1),
+ _vstatus_sub(-1),
+ _params_sub(-1),
+ _manual_control_sub(-1),
+
+/* publications */
+ _triplet_pub(-1),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
+/* states */
+ _mission_items_maxcount(20),
+ _mission_valid(false),
+ _loiter_hold(false)
+{
+ _mission_items = (mission_item_s*)malloc(sizeof(mission_item_s) * _mission_items_maxcount);
+ if (!_mission_items) {
+ _mission_items_maxcount = 0;
+ warnx("no free RAM to allocate mission, rejecting any waypoints");
+ }
+
+ _parameter_handles.throttle_cruise = param_find("NAV_DUMMY");
+
+ /* fetch initial parameter values */
+ parameters_update();
+}
+
+Navigator::~Navigator()
+{
+ if (_navigator_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(_navigator_task);
+ break;
+ }
+ } while (_navigator_task != -1);
+ }
+
+ navigator::g_navigator = nullptr;
+}
+
+int
+Navigator::parameters_update()
+{
+
+ //param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+
+ return OK;
+}
+
+void
+Navigator::vehicle_status_poll()
+{
+ bool vstatus_updated;
+
+ /* Check HIL state if vehicle status has changed */
+ orb_check(_vstatus_sub, &vstatus_updated);
+
+ if (vstatus_updated) {
+
+ orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
+ }
+}
+
+void
+Navigator::vehicle_attitude_poll()
+{
+ /* check if there is a new position */
+ bool att_updated;
+ orb_check(_att_sub, &att_updated);
+
+ if (att_updated) {
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+ }
+}
+
+void
+Navigator::mission_poll()
+{
+ /* check if there is a new setpoint */
+ bool mission_updated;
+ orb_check(_mission_sub, &mission_updated);
+
+ if (mission_updated) {
+
+ struct mission_s mission;
+ orb_copy(ORB_ID(mission), _mission_sub, &mission);
+
+ // XXX this is not optimal yet, but a first prototype /
+ // test implementation
+
+ if (mission.count <= _mission_items_maxcount) {
+ /*
+ * Perform an atomic copy & state update
+ */
+ irqstate_t flags = irqsave();
+
+ memcpy(_mission_items, mission.items, mission.count * sizeof(struct mission_item_s));
+ _mission_valid = true;
+
+ irqrestore(flags);
+ } else {
+ warnx("mission larger than storage space");
+ }
+ }
+}
+
+void
+Navigator::task_main_trampoline(int argc, char *argv[])
+{
+ navigator::g_navigator->task_main();
+}
+
+void
+Navigator::task_main()
+{
+
+ /* inform about start */
+ warnx("Initializing..");
+ fflush(stdout);
+
+ /*
+ * do subscriptions
+ */
+ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _mission_sub = orb_subscribe(ORB_ID(mission));
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ _params_sub = orb_subscribe(ORB_ID(parameter_update));
+ _manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_vstatus_sub, 200);
+ /* rate limit position updates to 50 Hz */
+ orb_set_interval(_global_pos_sub, 20);
+
+ parameters_update();
+
+ /* wakeup source(s) */
+ struct pollfd fds[2];
+
+ /* Setup of loop */
+ fds[0].fd = _params_sub;
+ fds[0].events = POLLIN;
+ fds[1].fd = _global_pos_sub;
+ fds[1].events = POLLIN;
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 500ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+
+ /* timed out - periodic check for _task_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* 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;
+ }
+
+ perf_begin(_loop_perf);
+
+ /* 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 */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+
+ /* update parameters from storage */
+ parameters_update();
+ }
+
+ /* only run controller if position changed */
+ if (fds[1].revents & POLLIN) {
+
+
+ static uint64_t last_run = 0;
+ float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+ /* guard against too large deltaT's */
+ if (deltaT > 1.0f)
+ deltaT = 0.01f;
+
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+
+ vehicle_attitude_poll();
+
+ mission_poll();
+
+ math::Vector2f ground_speed(_global_pos.vx, _global_pos.vy);
+ // Current waypoint
+ math::Vector2f next_wp(_global_triplet.current.lat / 1e7f, _global_triplet.current.lon / 1e7f);
+ // Global position
+ math::Vector2f current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
+
+ /* AUTONOMOUS FLIGHT */
+
+ if (1 /* autonomous flight */) {
+
+ /* execute navigation once we have a setpoint */
+ if (_mission_valid) {
+
+ // Next waypoint
+ math::Vector2f prev_wp;
+
+ if (_global_triplet.previous_valid) {
+ prev_wp.setX(_global_triplet.previous.lat / 1e7f);
+ prev_wp.setY(_global_triplet.previous.lon / 1e7f);
+
+ } else {
+ /*
+ * No valid next waypoint, go for heading hold.
+ * This is automatically handled by the L1 library.
+ */
+ prev_wp.setX(_global_triplet.current.lat / 1e7f);
+ prev_wp.setY(_global_triplet.current.lon / 1e7f);
+
+ }
+
+
+
+ /******** MAIN NAVIGATION STATE MACHINE ********/
+
+ // XXX to be put in its own class
+
+ if (_global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
+ /* waypoint is a plain navigation waypoint */
+
+
+ } else if (_global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+
+ /* waypoint is a loiter waypoint */
+
+ }
+
+ // XXX at this point we always want no loiter hold if a
+ // mission is active
+ _loiter_hold = false;
+
+ } else {
+
+ if (!_loiter_hold) {
+ _loiter_hold_lat = _global_pos.lat / 1e7f;
+ _loiter_hold_lon = _global_pos.lon / 1e7f;
+ _loiter_hold_alt = _global_pos.alt;
+ _loiter_hold = true;
+ }
+
+ //_parameters.loiter_hold_radius
+ }
+
+ } else if (0/* seatbelt mode enabled */) {
+
+ /** SEATBELT FLIGHT **/
+ continue;
+
+ } else {
+
+ /** MANUAL FLIGHT **/
+
+ /* no flight mode applies, do not publish an attitude setpoint */
+ continue;
+ }
+
+ /******** MAIN NAVIGATION STATE MACHINE ********/
+
+ if (_global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
+ // XXX define launch position and return
+
+ } else if (_global_triplet.current.nav_cmd == NAV_CMD_LAND) {
+ // XXX flared descent on final approach
+
+ } else if (_global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+
+ /* apply minimum pitch if altitude has not yet been reached */
+ if (_global_pos.alt < _global_triplet.current.altitude) {
+ _att_sp.pitch_body = math::max(_att_sp.pitch_body, _global_triplet.current.param1);
+ }
+ }
+
+ /* lazily publish the setpoint only once available */
+ if (_triplet_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_global_position_set_triplet), _triplet_pub, &_global_triplet);
+
+ } else {
+ /* advertise and publish */
+ _triplet_pub = orb_advertise(ORB_ID(vehicle_global_position_set_triplet), &_global_triplet);
+ }
+
+ }
+
+ perf_end(_loop_perf);
+ }
+
+ warnx("exiting.\n");
+
+ _navigator_task = -1;
+ _exit(0);
+}
+
+int
+Navigator::start()
+{
+ ASSERT(_navigator_task == -1);
+
+ /* start the task */
+ _navigator_task = task_spawn_cmd("navigator",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Navigator::task_main_trampoline,
+ nullptr);
+
+ if (_navigator_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int navigator_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: navigator {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (navigator::g_navigator != nullptr)
+ errx(1, "already running");
+
+ navigator::g_navigator = new Navigator;
+
+ if (navigator::g_navigator == nullptr)
+ errx(1, "alloc failed");
+
+ if (OK != navigator::g_navigator->start()) {
+ delete navigator::g_navigator;
+ navigator::g_navigator = nullptr;
+ err(1, "start failed");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (navigator::g_navigator == nullptr)
+ errx(1, "not running");
+
+ delete navigator::g_navigator;
+ navigator::g_navigator = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (navigator::g_navigator) {
+ errx(0, "running");
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
diff --git a/src/modules/mathlib/mathlib.h b/src/modules/navigator/navigator_params.c
index b919d53db..06df9a452 100644
--- a/src/modules/mathlib/mathlib.h
+++ b/src/modules/navigator/navigator_params.c
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,24 +33,21 @@
****************************************************************************/
/**
- * @file mathlib.h
+ * @file navigator_params.c
*
- * Common header for mathlib exports.
+ * Parameters defined by the navigator task.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
-#ifdef __cplusplus
-
-#include "math/Dcm.hpp"
-#include "math/EulerAngles.hpp"
-#include "math/Matrix.hpp"
-#include "math/Quaternion.hpp"
-#include "math/Vector.hpp"
-#include "math/Vector3.hpp"
+#include <nuttx/config.h>
-#endif
+#include <systemlib/param/param.h>
-#ifdef CONFIG_ARCH_ARM
+/*
+ * Navigator parameters, accessible via MAVLink
+ *
+ */
-#include "CMSIS/Include/arm_math.h"
+PARAM_DEFINE_FLOAT(NAV_DUMMY, 0.0f);
-#endif \ No newline at end of file
diff --git a/src/modules/position_estimator_inav/inertial_filter.c b/src/modules/position_estimator_inav/inertial_filter.c
new file mode 100644
index 000000000..13328edb4
--- /dev/null
+++ b/src/modules/position_estimator_inav/inertial_filter.c
@@ -0,0 +1,31 @@
+/*
+ * inertial_filter.c
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include "inertial_filter.h"
+
+void inertial_filter_predict(float dt, float x[3])
+{
+ x[0] += x[1] * dt + x[2] * dt * dt / 2.0f;
+ x[1] += x[2] * dt;
+}
+
+void inertial_filter_correct(float e, float dt, float x[3], int i, float w)
+{
+ float ewdt = w * dt;
+ if (ewdt > 1.0f)
+ ewdt = 1.0f; // prevent over-correcting
+ ewdt *= e;
+ x[i] += ewdt;
+
+ if (i == 0) {
+ x[1] += w * ewdt;
+ x[2] += w * w * ewdt / 3.0;
+
+ } else if (i == 1) {
+ x[2] += w * ewdt;
+ }
+}
diff --git a/src/modules/position_estimator_inav/inertial_filter.h b/src/modules/position_estimator_inav/inertial_filter.h
new file mode 100644
index 000000000..761c17097
--- /dev/null
+++ b/src/modules/position_estimator_inav/inertial_filter.h
@@ -0,0 +1,13 @@
+/*
+ * inertial_filter.h
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include <stdbool.h>
+#include <drivers/drv_hrt.h>
+
+void inertial_filter_predict(float dt, float x[3]);
+
+void inertial_filter_correct(float e, float dt, float x[3], int i, float w);
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
new file mode 100644
index 000000000..939d76849
--- /dev/null
+++ b/src/modules/position_estimator_inav/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Makefile to build position_estimator_inav
+#
+
+MODULE_COMMAND = position_estimator_inav
+SRCS = position_estimator_inav_main.c \
+ position_estimator_inav_params.c \
+ inertial_filter.c
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
new file mode 100644
index 000000000..3084b6d92
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -0,0 +1,652 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * 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 position_estimator_inav_main.c
+ * Model-identification based position estimator for multirotors
+ */
+
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <float.h>
+#include <string.h>
+#include <nuttx/config.h>
+#include <nuttx/sched.h>
+#include <sys/prctl.h>
+#include <termios.h>
+#include <errno.h>
+#include <limits.h>
+#include <math.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/optical_flow.h>
+#include <mavlink/mavlink_log.h>
+#include <poll.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+#include <systemlib/systemlib.h>
+#include <drivers/drv_hrt.h>
+
+#include "position_estimator_inav_params.h"
+#include "inertial_filter.h"
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+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 gps_timeout = 1000000; // GPS timeout = 1s
+static const hrt_abstime flow_timeout = 1000000; // optical flow timeout = 1s
+static const uint32_t updates_counter_len = 1000000;
+static const uint32_t pub_interval = 4000; // limit publish rate to 250 Hz
+
+__EXPORT int position_estimator_inav_main(int argc, char *argv[]);
+
+int position_estimator_inav_thread_main(int argc, char *argv[]);
+
+static void usage(const char *reason);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr,
+ "usage: position_estimator_inav {start|stop|status} [-v]\n\n");
+ exit(1);
+}
+
+/**
+ * The position_estimator_inav_thread only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int position_estimator_inav_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+ if (thread_running) {
+ printf("position_estimator_inav already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ verbose_mode = false;
+
+ if (argc > 1)
+ if (!strcmp(argv[2], "-v"))
+ verbose_mode = true;
+
+ thread_should_exit = false;
+ position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
+ SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096,
+ position_estimator_inav_thread_main,
+ (argv) ? (const char **) &argv[2] : (const char **) NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ printf("\tposition_estimator_inav is running\n");
+
+ } else {
+ printf("\tposition_estimator_inav not started\n");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+/****************************************************************************
+ * main
+ ****************************************************************************/
+int position_estimator_inav_thread_main(int argc, char *argv[])
+{
+ warnx("started.");
+ int mavlink_fd;
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(mavlink_fd, "[inav] started");
+
+ /* initialize values */
+ float x_est[3] = { 0.0f, 0.0f, 0.0f };
+ float y_est[3] = { 0.0f, 0.0f, 0.0f };
+ float z_est[3] = { 0.0f, 0.0f, 0.0f };
+
+ int baro_init_cnt = 0;
+ int baro_init_num = 200;
+ float baro_alt0 = 0.0f; /* to determine while start up */
+ float alt_avg = 0.0f;
+ bool landed = true;
+ hrt_abstime landed_time = 0;
+ bool flag_armed = false;
+
+ uint32_t accel_counter = 0;
+ uint32_t baro_counter = 0;
+
+ /* declare and safely initialize all structs */
+ struct actuator_controls_s actuator;
+ memset(&actuator, 0, sizeof(actuator));
+ struct actuator_armed_s armed;
+ memset(&armed, 0, sizeof(armed));
+ struct sensor_combined_s sensor;
+ memset(&sensor, 0, sizeof(sensor));
+ struct vehicle_gps_position_s gps;
+ memset(&gps, 0, sizeof(gps));
+ struct vehicle_attitude_s att;
+ memset(&att, 0, sizeof(att));
+ struct vehicle_local_position_s local_pos;
+ memset(&local_pos, 0, sizeof(local_pos));
+ struct optical_flow_s flow;
+ memset(&flow, 0, sizeof(flow));
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
+
+ /* subscribe */
+ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
+ int actuator_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
+ int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
+ int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+ 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));
+
+ /* advertise */
+ orb_advert_t vehicle_local_position_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos);
+ orb_advert_t vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
+
+ struct position_estimator_inav_params params;
+ struct position_estimator_inav_param_handles pos_inav_param_handles;
+ /* initialize parameter handles */
+ parameters_init(&pos_inav_param_handles);
+
+ /* first parameters read at start up */
+ struct parameter_update_s param_update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &param_update); /* read from param topic to clear updated flag */
+ /* first parameters update */
+ parameters_update(&pos_inav_param_handles, &params);
+
+ struct pollfd fds_init[1] = {
+ { .fd = sensor_combined_sub, .events = POLLIN },
+ };
+
+ /* wait for initial baro value */
+ bool wait_baro = true;
+
+ thread_running = true;
+
+ while (wait_baro && !thread_should_exit) {
+ int ret = poll(fds_init, 1, 1000);
+
+ if (ret < 0) {
+ /* poll error */
+ mavlink_log_info(mavlink_fd, "[inav] poll error on init");
+
+ } else if (ret > 0) {
+ if (fds_init[0].revents & POLLIN) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+
+ if (wait_baro && sensor.baro_counter != baro_counter) {
+ baro_counter = sensor.baro_counter;
+
+ /* mean calculation over several measurements */
+ if (baro_init_cnt < baro_init_num) {
+ baro_alt0 += sensor.baro_alt_meter;
+ baro_init_cnt++;
+
+ } else {
+ wait_baro = false;
+ baro_alt0 /= (float) baro_init_cnt;
+ warnx("init baro: alt = %.3f", baro_alt0);
+ mavlink_log_info(mavlink_fd, "[inav] init baro: alt = %.3f", baro_alt0);
+ local_pos.ref_alt = baro_alt0;
+ local_pos.ref_timestamp = hrt_absolute_time();
+ local_pos.z_valid = true;
+ local_pos.v_z_valid = true;
+ local_pos.z_global = true;
+ }
+ }
+ }
+ }
+ }
+
+ bool ref_xy_inited = false;
+ hrt_abstime ref_xy_init_start = 0;
+ const hrt_abstime ref_xy_init_delay = 5000000; // wait for 5s after 3D fix
+
+ hrt_abstime t_prev = 0;
+
+ uint16_t accel_updates = 0;
+ uint16_t baro_updates = 0;
+ uint16_t gps_updates = 0;
+ uint16_t attitude_updates = 0;
+ uint16_t flow_updates = 0;
+
+ hrt_abstime updates_counter_start = hrt_absolute_time();
+ hrt_abstime pub_last = hrt_absolute_time();
+
+ /* acceleration in NED frame */
+ float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G };
+
+ /* store error when sensor updates, but correct on each time step to avoid jumps in estimated value */
+ float accel_corr[] = { 0.0f, 0.0f, 0.0f }; // N E D
+ float accel_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
+ float baro_corr = 0.0f; // D
+ float gps_corr[2][2] = {
+ { 0.0f, 0.0f }, // N (pos, vel)
+ { 0.0f, 0.0f }, // E (pos, vel)
+ };
+ float sonar_corr = 0.0f;
+ float sonar_corr_filtered = 0.0f;
+ float flow_corr[] = { 0.0f, 0.0f }; // X, Y
+
+ float sonar_prev = 0.0f;
+ hrt_abstime sonar_time = 0;
+
+ /* main loop */
+ struct pollfd fds[7] = {
+ { .fd = parameter_update_sub, .events = POLLIN },
+ { .fd = actuator_sub, .events = POLLIN },
+ { .fd = armed_sub, .events = POLLIN },
+ { .fd = vehicle_attitude_sub, .events = POLLIN },
+ { .fd = sensor_combined_sub, .events = POLLIN },
+ { .fd = optical_flow_sub, .events = POLLIN },
+ { .fd = vehicle_gps_position_sub, .events = POLLIN }
+ };
+
+ if (!thread_should_exit) {
+ warnx("main loop started.");
+ }
+
+ while (!thread_should_exit) {
+ int ret = poll(fds, 7, 10); // wait maximal this 10 ms = 100 Hz minimum rate
+ hrt_abstime t = hrt_absolute_time();
+
+ if (ret < 0) {
+ /* poll error */
+ mavlink_log_info(mavlink_fd, "[inav] poll error on init");
+ continue;
+
+ } else if (ret > 0) {
+ /* parameter update */
+ if (fds[0].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub,
+ &update);
+ /* update parameters */
+ parameters_update(&pos_inav_param_handles, &params);
+ }
+
+ /* actuator */
+ if (fds[1].revents & POLLIN) {
+ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_sub, &actuator);
+ }
+
+ /* armed */
+ if (fds[2].revents & POLLIN) {
+ orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
+ }
+
+ /* vehicle attitude */
+ if (fds[3].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+ attitude_updates++;
+ }
+
+ /* sensor combined */
+ if (fds[4].revents & POLLIN) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+
+ if (sensor.accelerometer_counter != accel_counter) {
+ if (att.R_valid) {
+ /* correct accel bias, now only for Z */
+ sensor.accelerometer_m_s2[2] -= accel_bias[2];
+
+ /* transform acceleration vector from body frame to NED frame */
+ for (int i = 0; i < 3; i++) {
+ accel_NED[i] = 0.0f;
+
+ for (int j = 0; j < 3; j++) {
+ accel_NED[i] += att.R[i][j] * sensor.accelerometer_m_s2[j];
+ }
+ }
+
+ accel_corr[0] = accel_NED[0] - x_est[2];
+ accel_corr[1] = accel_NED[1] - y_est[2];
+ accel_corr[2] = accel_NED[2] + CONSTANTS_ONE_G - z_est[2];
+
+ } else {
+ memset(accel_corr, 0, sizeof(accel_corr));
+ }
+
+ accel_counter = sensor.accelerometer_counter;
+ accel_updates++;
+ }
+
+ if (sensor.baro_counter != baro_counter) {
+ baro_corr = - sensor.baro_alt_meter - z_est[0];
+ baro_counter = sensor.baro_counter;
+ baro_updates++;
+ }
+ }
+
+ /* optical flow */
+ if (fds[5].revents & POLLIN) {
+ orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow);
+
+ if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && (flow.ground_distance_m != sonar_prev || t - sonar_time < 150000)) {
+ if (flow.ground_distance_m != sonar_prev) {
+ sonar_time = t;
+ sonar_prev = flow.ground_distance_m;
+ sonar_corr = -flow.ground_distance_m - z_est[0];
+ sonar_corr_filtered += (sonar_corr - sonar_corr_filtered) * params.sonar_filt;
+
+ if (fabsf(sonar_corr) > params.sonar_err) {
+ // correction is too large: spike or new ground level?
+ if (fabsf(sonar_corr - sonar_corr_filtered) > params.sonar_err) {
+ // spike detected, ignore
+ sonar_corr = 0.0f;
+
+ } else {
+ // new ground level
+ baro_alt0 += sonar_corr;
+ mavlink_log_info(mavlink_fd, "[inav] new home: alt = %.3f", baro_alt0);
+ local_pos.ref_alt = baro_alt0;
+ local_pos.ref_timestamp = hrt_absolute_time();
+ z_est[0] += sonar_corr;
+ sonar_corr = 0.0f;
+ sonar_corr_filtered = 0.0f;
+ }
+ }
+ }
+
+ } else {
+ sonar_corr = 0.0f;
+ }
+
+ flow_updates++;
+ }
+
+ /* vehicle GPS position */
+ if (fds[6].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
+
+ if (gps.fix_type >= 3 && t < gps.timestamp_position + gps_timeout) {
+ /* initialize reference position if needed */
+ if (!ref_xy_inited) {
+ /* require EPH < 10m */
+ if (gps.eph_m < 10.0f) {
+ if (ref_xy_init_start == 0) {
+ ref_xy_init_start = t;
+
+ } else if (t > ref_xy_init_start + ref_xy_init_delay) {
+ ref_xy_inited = true;
+ /* reference GPS position */
+ double lat = gps.lat * 1e-7;
+ double lon = gps.lon * 1e-7;
+
+ local_pos.ref_lat = gps.lat;
+ local_pos.ref_lon = gps.lon;
+ local_pos.ref_timestamp = t;
+
+ /* initialize projection */
+ map_projection_init(lat, lon);
+ warnx("init GPS: lat = %.10f, lon = %.10f", lat, lon);
+ mavlink_log_info(mavlink_fd, "[inav] init GPS: %.7f, %.7f", lat, lon);
+ }
+ } else {
+ ref_xy_init_start = 0;
+ }
+ }
+
+ if (ref_xy_inited) {
+ /* project GPS lat lon to plane */
+ float gps_proj[2];
+ map_projection_project(gps.lat * 1e-7, gps.lon * 1e-7, &(gps_proj[0]), &(gps_proj[1]));
+ /* calculate correction for position */
+ gps_corr[0][0] = gps_proj[0] - x_est[0];
+ gps_corr[1][0] = gps_proj[1] - y_est[0];
+
+ /* calculate correction for velocity */
+ if (gps.vel_ned_valid) {
+ gps_corr[0][1] = gps.vel_n_m_s - x_est[1];
+ gps_corr[1][1] = gps.vel_e_m_s - y_est[1];
+
+ } else {
+ gps_corr[0][1] = 0.0f;
+ gps_corr[1][1] = 0.0f;
+ }
+ }
+
+ } else {
+ /* no GPS lock */
+ memset(gps_corr, 0, sizeof(gps_corr));
+ ref_xy_init_start = 0;
+ }
+
+ gps_updates++;
+ }
+ }
+
+ /* end of poll return value check */
+
+ float dt = t_prev > 0 ? (t - t_prev) / 1000000.0f : 0.0f;
+ t_prev = t;
+
+ /* reset ground level on arm */
+ if (armed.armed && !flag_armed) {
+ baro_alt0 -= z_est[0];
+ z_est[0] = 0.0f;
+ local_pos.ref_alt = baro_alt0;
+ local_pos.ref_timestamp = hrt_absolute_time();
+ mavlink_log_info(mavlink_fd, "[inav] new home on arm: alt = %.3f", baro_alt0);
+ }
+
+ /* accel bias correction, now only for Z
+ * not strictly correct, but stable and works */
+ accel_bias[2] += (accel_NED[2] + CONSTANTS_ONE_G) * params.w_acc_bias * dt;
+
+ /* inertial filter prediction for altitude */
+ inertial_filter_predict(dt, z_est);
+
+ /* inertial filter correction for altitude */
+ baro_alt0 += sonar_corr * params.w_alt_sonar * dt;
+ inertial_filter_correct(baro_corr + baro_alt0, dt, z_est, 0, params.w_alt_baro);
+ inertial_filter_correct(sonar_corr, dt, z_est, 0, params.w_alt_sonar);
+ inertial_filter_correct(accel_corr[2], dt, z_est, 2, params.w_alt_acc);
+
+ bool gps_valid = ref_xy_inited && gps.fix_type >= 3 && t < gps.timestamp_position + gps_timeout;
+ bool flow_valid = false; // TODO implement opt flow
+
+ /* try to estimate xy even if no absolute position source available,
+ * if using optical flow velocity will be correct in this case */
+ bool can_estimate_xy = gps_valid || flow_valid;
+
+ if (can_estimate_xy) {
+ /* inertial filter prediction for position */
+ inertial_filter_predict(dt, x_est);
+ inertial_filter_predict(dt, y_est);
+
+ /* inertial filter correction for position */
+ inertial_filter_correct(accel_corr[0], dt, x_est, 2, params.w_pos_acc);
+ inertial_filter_correct(accel_corr[1], dt, y_est, 2, params.w_pos_acc);
+
+ if (gps_valid) {
+ inertial_filter_correct(gps_corr[0][0], dt, x_est, 0, params.w_pos_gps_p);
+ inertial_filter_correct(gps_corr[1][0], dt, y_est, 0, params.w_pos_gps_p);
+
+ if (gps.vel_ned_valid && t < gps.timestamp_velocity + gps_timeout) {
+ inertial_filter_correct(gps_corr[0][1], dt, x_est, 1, params.w_pos_gps_v);
+ inertial_filter_correct(gps_corr[1][1], dt, y_est, 1, params.w_pos_gps_v);
+ }
+ }
+ }
+
+ /* detect land */
+ alt_avg += (z_est[0] - alt_avg) * dt / params.land_t;
+ float alt_disp = z_est[0] - alt_avg;
+ alt_disp = alt_disp * alt_disp;
+ float land_disp2 = params.land_disp * params.land_disp;
+ /* get actual thrust output */
+ float thrust = armed.armed ? actuator.control[3] : 0.0f;
+
+ if (landed) {
+ if (alt_disp > land_disp2 && thrust > params.land_thr) {
+ landed = false;
+ landed_time = 0;
+ }
+
+ } else {
+ if (alt_disp < land_disp2 && thrust < params.land_thr) {
+ if (landed_time == 0) {
+ landed_time = t; // land detected first time
+
+ } else {
+ if (t > landed_time + params.land_t * 1000000.0f) {
+ landed = true;
+ landed_time = 0;
+ }
+ }
+
+ } else {
+ landed_time = 0;
+ }
+ }
+
+ if (verbose_mode) {
+ /* print updates rate */
+ if (t > updates_counter_start + updates_counter_len) {
+ float updates_dt = (t - updates_counter_start) * 0.000001f;
+ warnx(
+ "updates rate: accelerometer = %.1f/s, baro = %.1f/s, gps = %.1f/s, attitude = %.1f/s, flow = %.1f/s",
+ accel_updates / updates_dt,
+ baro_updates / updates_dt,
+ gps_updates / updates_dt,
+ attitude_updates / updates_dt,
+ flow_updates / updates_dt);
+ updates_counter_start = t;
+ accel_updates = 0;
+ baro_updates = 0;
+ gps_updates = 0;
+ attitude_updates = 0;
+ flow_updates = 0;
+ }
+ }
+
+ if (t > pub_last + pub_interval) {
+ pub_last = t;
+ /* publish local position */
+ local_pos.timestamp = t;
+ local_pos.xy_valid = can_estimate_xy && gps_valid;
+ local_pos.v_xy_valid = can_estimate_xy;
+ local_pos.xy_global = local_pos.xy_valid && gps_valid; // will make sense when local position sources (e.g. vicon) will be implemented
+ local_pos.x = x_est[0];
+ local_pos.vx = x_est[1];
+ local_pos.y = y_est[0];
+ local_pos.vy = y_est[1];
+ local_pos.z = z_est[0];
+ local_pos.vz = z_est[1];
+ local_pos.landed = landed;
+ local_pos.yaw = att.yaw;
+
+ orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos);
+
+ /* publish global position */
+ global_pos.valid = local_pos.xy_global;
+
+ if (local_pos.xy_global) {
+ double est_lat, est_lon;
+ map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon);
+ global_pos.lat = (int32_t)(est_lat * 1e7);
+ global_pos.lon = (int32_t)(est_lon * 1e7);
+ global_pos.time_gps_usec = gps.time_gps_usec;
+ }
+
+ /* set valid values even if position is not valid */
+ if (local_pos.v_xy_valid) {
+ global_pos.vx = local_pos.vx;
+ global_pos.vy = local_pos.vy;
+ }
+
+ if (local_pos.z_valid) {
+ global_pos.relative_alt = -local_pos.z;
+ }
+
+ if (local_pos.z_global) {
+ global_pos.alt = local_pos.ref_alt - local_pos.z;
+ }
+
+ if (local_pos.v_z_valid) {
+ global_pos.vz = local_pos.vz;
+ }
+ global_pos.yaw = local_pos.yaw;
+
+ global_pos.timestamp = t;
+
+ orb_publish(ORB_ID(vehicle_global_position), vehicle_global_position_pub, &global_pos);
+ }
+ flag_armed = armed.armed;
+ }
+
+ warnx("exiting.");
+ mavlink_log_info(mavlink_fd, "[inav] exiting");
+ thread_running = false;
+ return 0;
+}
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
new file mode 100644
index 000000000..4f9ddd009
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -0,0 +1,96 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * 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 position_estimator_inav_params.c
+ *
+ * Parameters for position_estimator_inav
+ */
+
+#include "position_estimator_inav_params.h"
+
+PARAM_DEFINE_FLOAT(INAV_W_ALT_BARO, 0.5f);
+PARAM_DEFINE_FLOAT(INAV_W_ALT_ACC, 50.0f);
+PARAM_DEFINE_FLOAT(INAV_W_ALT_SONAR, 3.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_GPS_P, 1.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_GPS_V, 2.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_ACC, 10.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_FLOW, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_FLOW_K, 1.0f);
+PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.02f);
+PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
+PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
+PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
+PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.3f);
+
+int parameters_init(struct position_estimator_inav_param_handles *h)
+{
+ h->w_alt_baro = param_find("INAV_W_ALT_BARO");
+ h->w_alt_acc = param_find("INAV_W_ALT_ACC");
+ h->w_alt_sonar = param_find("INAV_W_ALT_SONAR");
+ h->w_pos_gps_p = param_find("INAV_W_POS_GPS_P");
+ h->w_pos_gps_v = param_find("INAV_W_POS_GPS_V");
+ h->w_pos_acc = param_find("INAV_W_POS_ACC");
+ h->w_pos_flow = param_find("INAV_W_POS_FLOW");
+ h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
+ h->flow_k = param_find("INAV_FLOW_K");
+ h->sonar_filt = param_find("INAV_SONAR_FILT");
+ h->sonar_err = param_find("INAV_SONAR_ERR");
+ h->land_t = param_find("INAV_LAND_T");
+ h->land_disp = param_find("INAV_LAND_DISP");
+ h->land_thr = param_find("INAV_LAND_THR");
+
+ return OK;
+}
+
+int parameters_update(const struct position_estimator_inav_param_handles *h, struct position_estimator_inav_params *p)
+{
+ param_get(h->w_alt_baro, &(p->w_alt_baro));
+ param_get(h->w_alt_acc, &(p->w_alt_acc));
+ param_get(h->w_alt_sonar, &(p->w_alt_sonar));
+ param_get(h->w_pos_gps_p, &(p->w_pos_gps_p));
+ param_get(h->w_pos_gps_v, &(p->w_pos_gps_v));
+ param_get(h->w_pos_acc, &(p->w_pos_acc));
+ param_get(h->w_pos_flow, &(p->w_pos_flow));
+ param_get(h->w_acc_bias, &(p->w_acc_bias));
+ param_get(h->flow_k, &(p->flow_k));
+ param_get(h->sonar_filt, &(p->sonar_filt));
+ param_get(h->sonar_err, &(p->sonar_err));
+ param_get(h->land_t, &(p->land_t));
+ param_get(h->land_disp, &(p->land_disp));
+ param_get(h->land_thr, &(p->land_thr));
+
+ 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
new file mode 100644
index 000000000..61570aea7
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * 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 position_estimator_inav_params.h
+ *
+ * Parameters for Position Estimator
+ */
+
+#include <systemlib/param/param.h>
+
+struct position_estimator_inav_params {
+ float w_alt_baro;
+ float w_alt_acc;
+ float w_alt_sonar;
+ float w_pos_gps_p;
+ float w_pos_gps_v;
+ float w_pos_acc;
+ float w_pos_flow;
+ float w_acc_bias;
+ float flow_k;
+ float sonar_filt;
+ float sonar_err;
+ float land_t;
+ float land_disp;
+ float land_thr;
+};
+
+struct position_estimator_inav_param_handles {
+ param_t w_alt_baro;
+ param_t w_alt_acc;
+ param_t w_alt_sonar;
+ param_t w_pos_gps_p;
+ param_t w_pos_gps_v;
+ param_t w_pos_acc;
+ param_t w_pos_flow;
+ param_t w_acc_bias;
+ param_t flow_k;
+ param_t sonar_filt;
+ param_t sonar_err;
+ param_t land_t;
+ param_t land_disp;
+ param_t land_thr;
+};
+
+/**
+ * Initialize all parameter handles and values
+ *
+ */
+int parameters_init(struct position_estimator_inav_param_handles *h);
+
+/**
+ * Update all parameters
+ *
+ */
+int parameters_update(const struct position_estimator_inav_param_handles *h, struct position_estimator_inav_params *p);
diff --git a/src/modules/position_estimator_mc/position_estimator_mc_main.c b/src/modules/position_estimator_mc/position_estimator_mc_main.c
index 984bd1329..363961819 100755
--- a/src/modules/position_estimator_mc/position_estimator_mc_main.c
+++ b/src/modules/position_estimator_mc/position_estimator_mc_main.c
@@ -497,7 +497,12 @@ int position_estimator_mc_thread_main(int argc, char *argv[])
local_pos_est.vz = x_z_aposteriori_k[1];
local_pos_est.timestamp = hrt_absolute_time();
if ((isfinite(x_x_aposteriori_k[0])) && (isfinite(x_x_aposteriori_k[1])) && (isfinite(x_y_aposteriori_k[0])) && (isfinite(x_y_aposteriori_k[1])) && (isfinite(x_z_aposteriori_k[0])) && (isfinite(x_z_aposteriori_k[1]))){
- orb_publish(ORB_ID(vehicle_local_position), local_pos_est_pub, &local_pos_est);
+ if(local_pos_est_pub > 0)
+ orb_publish(ORB_ID(vehicle_local_position), local_pos_est_pub, &local_pos_est);
+ else
+ local_pos_est_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos_est);
+ //char buf[0xff]; sprintf(buf,"[pos_est_mc] x:%f, y:%f, z:%f",x_x_aposteriori_k[0],x_y_aposteriori_k[0],x_z_aposteriori_k[0]);
+ //mavlink_log_info(mavlink_fd, buf);
}
}
} /* end of poll return value check */
diff --git a/src/modules/px4iofirmware/adc.c b/src/modules/px4iofirmware/adc.c
index 81566eb2a..2f5908ac5 100644
--- a/src/modules/px4iofirmware/adc.c
+++ b/src/modules/px4iofirmware/adc.c
@@ -83,6 +83,14 @@ adc_init(void)
{
adc_perf = perf_alloc(PC_ELAPSED, "adc");
+ /* put the ADC into power-down mode */
+ rCR2 &= ~ADC_CR2_ADON;
+ up_udelay(10);
+
+ /* bring the ADC out of power-down mode */
+ rCR2 |= ADC_CR2_ADON;
+ up_udelay(10);
+
/* do calibration if supported */
#ifdef ADC_CR2_CAL
rCR2 |= ADC_CR2_RSTCAL;
@@ -96,41 +104,25 @@ adc_init(void)
if (rCR2 & ADC_CR2_CAL)
return -1;
-
#endif
- /* arbitrarily configure all channels for 55 cycle sample time */
- rSMPR1 = 0b00000011011011011011011011011011;
+ /*
+ * Configure sampling time.
+ *
+ * For electrical protection reasons, we want to be able to have
+ * 10K in series with ADC inputs that leave the board. At 12MHz this
+ * means we need 28.5 cycles of sampling time (per table 43 in the
+ * datasheet).
+ */
+ rSMPR1 = 0b00000000011011011011011011011011;
rSMPR2 = 0b00011011011011011011011011011011;
- /* XXX for F2/4, might want to select 12-bit mode? */
- rCR1 = 0;
-
- /* enable the temperature sensor / Vrefint channel if supported*/
- rCR2 =
-#ifdef ADC_CR2_TSVREFE
- /* enable the temperature sensor in CR2 */
- ADC_CR2_TSVREFE |
-#endif
- 0;
-
-#ifdef ADC_CCR_TSVREFE
- /* enable temperature sensor in CCR */
- rCCR = ADC_CCR_TSVREFE;
-#endif
+ rCR2 |= ADC_CR2_TSVREFE; /* enable the temperature sensor / Vrefint channel */
/* configure for a single-channel sequence */
rSQR1 = 0;
rSQR2 = 0;
- rSQR3 = 0; /* will be updated with the channel each tick */
-
- /* power-cycle the ADC and turn it on */
- rCR2 &= ~ADC_CR2_ADON;
- up_udelay(10);
- rCR2 |= ADC_CR2_ADON;
- up_udelay(10);
- rCR2 |= ADC_CR2_ADON;
- up_udelay(10);
+ rSQR3 = 0; /* will be updated with the channel at conversion time */
return 0;
}
@@ -141,11 +133,12 @@ adc_init(void)
uint16_t
adc_measure(unsigned channel)
{
+
perf_begin(adc_perf);
/* clear any previous EOC */
- if (rSR & ADC_SR_EOC)
- rSR &= ~ADC_SR_EOC;
+ rSR = 0;
+ (void)rDR;
/* run a single conversion right now - should take about 60 cycles (a few microseconds) max */
rSQR3 = channel;
@@ -158,7 +151,6 @@ adc_measure(unsigned channel)
/* never spin forever - this will give a bogus result though */
if (hrt_elapsed_time(&now) > 100) {
- debug("adc timeout");
perf_end(adc_perf);
return 0xffff;
}
@@ -166,6 +158,7 @@ adc_measure(unsigned channel)
/* read the result and clear EOC */
uint16_t result = rDR;
+ rSR = 0;
perf_end(adc_perf);
return result;
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 3cf9ca149..941500f0d 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -50,7 +50,7 @@
#define RC_CHANNEL_HIGH_THRESH 5000
#define RC_CHANNEL_LOW_THRESH -5000
-static bool ppm_input(uint16_t *values, uint16_t *num_values);
+static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
static perf_counter_t c_gather_dsm;
static perf_counter_t c_gather_sbus;
@@ -59,14 +59,19 @@ static perf_counter_t c_gather_ppm;
void
controls_init(void)
{
- /* DSM input */
+ /* no channels */
+ r_raw_rc_count = 0;
+ system_state.rc_channels_timestamp_received = 0;
+ system_state.rc_channels_timestamp_valid = 0;
+
+ /* DSM input (USART1) */
dsm_init("/dev/ttyS0");
- /* S.bus input */
+ /* S.bus input (USART3) */
sbus_init("/dev/ttyS2");
/* default to a 1:1 input map, all enabled */
- for (unsigned i = 0; i < MAX_CONTROL_CHANNELS; i++) {
+ for (unsigned i = 0; i < PX4IO_RC_INPUT_CHANNELS; i++) {
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = 0;
@@ -94,16 +99,67 @@ controls_tick() {
* other. Don't do that.
*/
+ /* receive signal strenght indicator (RSSI). 0 = no connection, 255: perfect connection */
+ uint16_t rssi = 0;
+
+#ifdef ADC_RSSI
+ if (r_setup_features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) {
+ unsigned counts = adc_measure(ADC_RSSI);
+ if (counts != 0xffff) {
+ /* use 1:1 scaling on 3.3V ADC input */
+ unsigned mV = counts * 3300 / 4096;
+
+ /* scale to 0..253 */
+ rssi = mV / 13;
+ }
+ }
+#endif
+
perf_begin(c_gather_dsm);
- bool dsm_updated = dsm_input(r_raw_rc_values, &r_raw_rc_count);
- if (dsm_updated)
- r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_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);
+
+ }
perf_end(c_gather_dsm);
perf_begin(c_gather_sbus);
- bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count);
- if (sbus_updated)
+
+ bool sbus_status = (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_SBUS);
+
+ bool sbus_failsafe, sbus_frame_drop;
+ bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, &sbus_failsafe, &sbus_frame_drop, PX4IO_RC_INPUT_CHANNELS);
+
+ if (sbus_updated) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS;
+
+ rssi = 255;
+
+ if (sbus_frame_drop) {
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FRAME_DROP;
+ rssi = 100;
+ } else {
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ }
+
+ if (sbus_failsafe) {
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FAILSAFE;
+ rssi = 0;
+ } else {
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ }
+
+ }
+
perf_end(c_gather_sbus);
/*
@@ -112,12 +168,21 @@ controls_tick() {
* disable the PPM decoder completely if we have S.bus signal.
*/
perf_begin(c_gather_ppm);
- bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count);
- if (ppm_updated)
+ bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_raw_rc_input[PX4IO_P_RAW_RC_DATA]);
+ if (ppm_updated) {
+
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
+ 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_ppm);
- ASSERT(r_raw_rc_count <= MAX_CONTROL_CHANNELS);
+ /* limit number of channels to allowable data size */
+ if (r_raw_rc_count > PX4IO_RC_INPUT_CHANNELS)
+ r_raw_rc_count = PX4IO_RC_INPUT_CHANNELS;
+
+ /* store RSSI */
+ r_page_raw_rc_input[PX4IO_P_RAW_RC_NRSSI] = rssi;
/*
* In some cases we may have received a frame, but input has still
@@ -130,95 +195,100 @@ controls_tick() {
*/
if (dsm_updated || sbus_updated || ppm_updated) {
- /* update RC-received timestamp */
- system_state.rc_channels_timestamp = hrt_absolute_time();
-
/* record a bitmask of channels assigned */
unsigned assigned_channels = 0;
- /* map raw inputs to mapped inputs */
- /* XXX mapping should be atomic relative to protocol */
- for (unsigned i = 0; i < r_raw_rc_count; i++) {
-
- /* map the input channel */
- uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE];
-
- if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
-
- uint16_t raw = r_raw_rc_values[i];
-
- int16_t scaled;
-
- /*
- * 1) Constrain to min/max values, as later processing depends on bounds.
- */
- if (raw < conf[PX4IO_P_RC_CONFIG_MIN])
- raw = conf[PX4IO_P_RC_CONFIG_MIN];
- if (raw > conf[PX4IO_P_RC_CONFIG_MAX])
- raw = conf[PX4IO_P_RC_CONFIG_MAX];
-
- /*
- * 2) Scale around the mid point differently for lower and upper range.
- *
- * This is necessary as they don't share the same endpoints and slope.
- *
- * First normalize to 0..1 range with correct sign (below or above center),
- * then scale to 20000 range (if center is an actual center, -10000..10000,
- * if parameters only support half range, scale to 10000 range, e.g. if
- * center == min 0..10000, if center == max -10000..0).
- *
- * As the min and max bounds were enforced in step 1), division by zero
- * cannot occur, as for the case of center == min or center == max the if
- * statement is mutually exclusive with the arithmetic NaN case.
- *
- * DO NOT REMOVE OR ALTER STEP 1!
- */
- if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
- scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]));
-
- } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
- scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN]));
-
- } else {
- /* in the configured dead zone, output zero */
- scaled = 0;
+ /* update RC-received timestamp */
+ system_state.rc_channels_timestamp_received = hrt_absolute_time();
+
+ /* do not command anything in failsafe, kick in the RC loss counter */
+ if (!(r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE)) {
+
+ /* update RC-received timestamp */
+ system_state.rc_channels_timestamp_valid = system_state.rc_channels_timestamp_received;
+
+ /* map raw inputs to mapped inputs */
+ /* XXX mapping should be atomic relative to protocol */
+ for (unsigned i = 0; i < r_raw_rc_count; i++) {
+
+ /* map the input channel */
+ uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE];
+
+ if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
+
+ uint16_t raw = r_raw_rc_values[i];
+
+ int16_t scaled;
+
+ /*
+ * 1) Constrain to min/max values, as later processing depends on bounds.
+ */
+ if (raw < conf[PX4IO_P_RC_CONFIG_MIN])
+ raw = conf[PX4IO_P_RC_CONFIG_MIN];
+ if (raw > conf[PX4IO_P_RC_CONFIG_MAX])
+ raw = conf[PX4IO_P_RC_CONFIG_MAX];
+
+ /*
+ * 2) Scale around the mid point differently for lower and upper range.
+ *
+ * This is necessary as they don't share the same endpoints and slope.
+ *
+ * First normalize to 0..1 range with correct sign (below or above center),
+ * then scale to 20000 range (if center is an actual center, -10000..10000,
+ * if parameters only support half range, scale to 10000 range, e.g. if
+ * center == min 0..10000, if center == max -10000..0).
+ *
+ * As the min and max bounds were enforced in step 1), division by zero
+ * cannot occur, as for the case of center == min or center == max the if
+ * statement is mutually exclusive with the arithmetic NaN case.
+ *
+ * DO NOT REMOVE OR ALTER STEP 1!
+ */
+ if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
+ scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]));
+
+ } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
+ scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN]));
+
+ } else {
+ /* in the configured dead zone, output zero */
+ scaled = 0;
+ }
+
+ /* invert channel if requested */
+ if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE)
+ scaled = -scaled;
+
+ /* and update the scaled/mapped version */
+ unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
+ if (mapped < PX4IO_CONTROL_CHANNELS) {
+
+ /* invert channel if pitch - pulling the lever down means pitching up by convention */
+ if (mapped == 1) /* roll, pitch, yaw, throttle, override is the standard order */
+ scaled = -scaled;
+
+ r_rc_values[mapped] = SIGNED_TO_REG(scaled);
+ assigned_channels |= (1 << mapped);
+
+ }
}
-
- /* invert channel if requested */
- if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE)
- scaled = -scaled;
-
- /* and update the scaled/mapped version */
- unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
- ASSERT(mapped < MAX_CONTROL_CHANNELS);
-
- /* invert channel if pitch - pulling the lever down means pitching up by convention */
- if (mapped == 1) /* roll, pitch, yaw, throttle, override is the standard order */
- scaled = -scaled;
-
- r_rc_values[mapped] = SIGNED_TO_REG(scaled);
- assigned_channels |= (1 << mapped);
}
- }
- /* set un-assigned controls to zero */
- for (unsigned i = 0; i < MAX_CONTROL_CHANNELS; i++) {
- if (!(assigned_channels & (1 << i)))
- r_rc_values[i] = 0;
- }
+ /* set un-assigned controls to zero */
+ for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++) {
+ if (!(assigned_channels & (1 << i)))
+ r_rc_values[i] = 0;
+ }
- /*
- * If we got an update with zero channels, treat it as
- * a loss of input.
- *
- * This might happen if a protocol-based receiver returns an update
- * that contains no channels that we have mapped.
- */
- if (assigned_channels == 0) {
- rc_input_lost = true;
- } else {
- /* set RC OK flag */
+ /* set RC OK flag, as we got an update */
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK;
+
+ /* if we have enough channels (5) to control the vehicle, the mapping is ok */
+ if (assigned_channels > 4) {
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_MAPPING_OK;
+ } else {
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_MAPPING_OK);
+ }
}
/*
@@ -231,7 +301,7 @@ controls_tick() {
* If we haven't seen any new control data in 200ms, assume we
* have lost input.
*/
- if (hrt_elapsed_time(&system_state.rc_channels_timestamp) > 200000) {
+ if (hrt_elapsed_time(&system_state.rc_channels_timestamp_received) > 200000) {
rc_input_lost = true;
/* clear the input-kind flags here */
@@ -239,24 +309,32 @@ controls_tick() {
PX4IO_P_STATUS_FLAGS_RC_PPM |
PX4IO_P_STATUS_FLAGS_RC_DSM |
PX4IO_P_STATUS_FLAGS_RC_SBUS);
+
}
/*
* Handle losing RC input
*/
- if (rc_input_lost) {
+ /* this kicks in if the receiver is gone or the system went to failsafe */
+ if (rc_input_lost || (r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE)) {
/* Clear the RC input status flag, clear manual override flag */
r_status_flags &= ~(
PX4IO_P_STATUS_FLAGS_OVERRIDE |
PX4IO_P_STATUS_FLAGS_RC_OK);
+ /* Mark all channels as invalid, as we just lost the RX */
+ r_rc_valid = 0;
+
/* Set the RC_LOST alarm */
r_status_alarms |= PX4IO_P_STATUS_ALARMS_RC_LOST;
+ }
+
+ /* this kicks in if the receiver is completely gone */
+ if (rc_input_lost) {
- /* Mark the arrays as empty */
+ /* Set channel count to zero */
r_raw_rc_count = 0;
- r_rc_valid = 0;
}
/*
@@ -279,7 +357,7 @@ controls_tick() {
* requested override.
*
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) > RC_CHANNEL_HIGH_THRESH))
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) < RC_CHANNEL_LOW_THRESH))
override = true;
if (override) {
@@ -293,11 +371,13 @@ controls_tick() {
} else {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
}
+ } else {
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
}
}
static bool
-ppm_input(uint16_t *values, uint16_t *num_values)
+ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
{
bool result = false;
@@ -312,8 +392,8 @@ ppm_input(uint16_t *values, uint16_t *num_values)
/* PPM data exists, copy it */
*num_values = ppm_decoded_channels;
- if (*num_values > MAX_CONTROL_CHANNELS)
- *num_values = MAX_CONTROL_CHANNELS;
+ if (*num_values > PX4IO_RC_INPUT_CHANNELS)
+ *num_values = PX4IO_RC_INPUT_CHANNELS;
for (unsigned i = 0; i < *num_values; i++)
values[i] = ppm_buffer[i];
@@ -321,6 +401,10 @@ ppm_input(uint16_t *values, uint16_t *num_values)
/* clear validity */
ppm_last_valid_decode = 0;
+ /* store PPM frame length */
+ if (num_values)
+ *frame_len = ppm_frame_length;
+
/* good if we got any channels */
result = (*num_values > 0);
}
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index ea35e5513..d3f365822 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -40,6 +40,7 @@
*/
#include <nuttx/config.h>
+#include <nuttx/arch.h>
#include <fcntl.h>
#include <unistd.h>
@@ -47,121 +48,44 @@
#include <drivers/drv_hrt.h>
-#define DEBUG
-
#include "px4io.h"
-#define DSM_FRAME_SIZE 16
-#define DSM_FRAME_CHANNELS 7
-
-static int dsm_fd = -1;
-
-static hrt_abstime last_rx_time;
-static hrt_abstime last_frame_time;
-
-static uint8_t frame[DSM_FRAME_SIZE];
-
-static unsigned partial_frame_count;
-static unsigned channel_shift;
-
-unsigned dsm_frame_drops;
-
-static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value);
-static void dsm_guess_format(bool reset);
-static bool dsm_decode(hrt_abstime now, uint16_t *values, uint16_t *num_values);
-
-int
-dsm_init(const char *device)
-{
- if (dsm_fd < 0)
- dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
-
- if (dsm_fd >= 0) {
- struct termios t;
+#define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/
+#define DSM_FRAME_CHANNELS 7 /**<Max supported DSM channels*/
- /* 115200bps, no parity, one stop bit */
- tcgetattr(dsm_fd, &t);
- cfsetspeed(&t, 115200);
- t.c_cflag &= ~(CSTOPB | PARENB);
- tcsetattr(dsm_fd, TCSANOW, &t);
-
- /* initialise the decoder */
- partial_frame_count = 0;
- last_rx_time = hrt_absolute_time();
-
- /* reset the format detector */
- dsm_guess_format(true);
-
- debug("DSM: ready");
-
- } else {
- debug("DSM: open failed");
- }
-
- return dsm_fd;
-}
-
-bool
-dsm_input(uint16_t *values, uint16_t *num_values)
-{
- ssize_t ret;
- hrt_abstime now;
-
- /*
- * The DSM* protocol doesn't provide any explicit framing,
- * so we detect frame boundaries by the inter-frame delay.
- *
- * The minimum frame spacing is 11ms; with 16 bytes at 115200bps
- * frame transmission time is ~1.4ms.
- *
- * We expect to only be called when bytes arrive for processing,
- * and if an interval of more than 5ms passes between calls,
- * the first byte we read will be the first byte of a frame.
- *
- * In the case where byte(s) are dropped from a frame, this also
- * provides a degree of protection. Of course, it would be better
- * if we didn't drop bytes...
- */
- now = hrt_absolute_time();
-
- if ((now - last_rx_time) > 5000) {
- if (partial_frame_count > 0) {
- dsm_frame_drops++;
- partial_frame_count = 0;
- }
- }
-
- /*
- * Fetch bytes, but no more than we would need to complete
- * the current frame.
- */
- ret = read(dsm_fd, &frame[partial_frame_count], DSM_FRAME_SIZE - partial_frame_count);
-
- /* if the read failed for any reason, just give up here */
- if (ret < 1)
- return false;
-
- last_rx_time = now;
-
- /*
- * Add bytes to the current frame
- */
- partial_frame_count += ret;
-
- /*
- * If we don't have a full frame, return
- */
- if (partial_frame_count < DSM_FRAME_SIZE)
- return false;
-
- /*
- * Great, it looks like we might have a frame. Go ahead and
- * decode it.
- */
- partial_frame_count = 0;
- return dsm_decode(now, values, num_values);
-}
+static int dsm_fd = -1; /**< File handle to the DSM UART */
+static hrt_abstime dsm_last_rx_time; /**< Timestamp when we last received */
+static hrt_abstime dsm_last_frame_time; /**< Timestamp for start of last dsm frame */
+static uint8_t dsm_frame[DSM_FRAME_SIZE]; /**< DSM dsm frame receive buffer */
+static unsigned dsm_partial_frame_count; /**< Count of bytes received for current dsm frame */
+static unsigned dsm_channel_shift; /**< Channel resolution, 0=unknown, 1=10 bit, 2=11 bit */
+static unsigned dsm_frame_drops; /**< Count of incomplete DSM frames */
+/**
+ * Attempt to decode a single channel raw channel datum
+ *
+ * The DSM* protocol doesn't provide any explicit framing,
+ * so we detect dsm frame boundaries by the inter-dsm frame delay.
+ *
+ * The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
+ * dsm frame transmission time is ~1.4ms.
+ *
+ * We expect to only be called when bytes arrive for processing,
+ * and if an interval of more than 5ms passes between calls,
+ * the first byte we read will be the first byte of a dsm frame.
+ *
+ * In the case where byte(s) are dropped from a dsm frame, this also
+ * provides a degree of protection. Of course, it would be better
+ * if we didn't drop bytes...
+ *
+ * Upon receiving a full dsm frame we attempt to decode it
+ *
+ * @param[in] raw 16 bit raw channel value from dsm frame
+ * @param[in] shift position of channel number in raw data
+ * @param[out] channel pointer to returned channel number
+ * @param[out] value pointer to returned channel value
+ * @return true=raw value successfully decoded
+ */
static bool
dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
{
@@ -179,6 +103,11 @@ dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *va
return true;
}
+/**
+ * Attempt to guess if receiving 10 or 11 bit channel values
+ *
+ * @param[in] reset true=reset the 10/11 bit state to unknown
+ */
static void
dsm_guess_format(bool reset)
{
@@ -191,14 +120,14 @@ dsm_guess_format(bool reset)
cs10 = 0;
cs11 = 0;
samples = 0;
- channel_shift = 0;
+ dsm_channel_shift = 0;
return;
}
- /* scan the channels in the current frame in both 10- and 11-bit mode */
+ /* scan the channels in the current dsm_frame in both 10- and 11-bit mode */
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
- uint8_t *dp = &frame[2 + (2 * i)];
+ uint8_t *dp = &dsm_frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
unsigned channel, value;
@@ -209,16 +138,16 @@ dsm_guess_format(bool reset)
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
cs11 |= (1 << channel);
- /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-frame format */
+ /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
}
- /* wait until we have seen plenty of frames - 2 should normally be enough */
+ /* wait until we have seen plenty of frames - 5 should normally be enough */
if (samples++ < 5)
return;
/*
* Iterate the set of sensible sniffed channel sets and see whether
- * decoding in 10 or 11-bit mode has yielded anything we recognise.
+ * decoding in 10 or 11-bit mode has yielded anything we recognize.
*
* XXX Note that due to what seem to be bugs in the DSM2 high-resolution
* stream, we may want to sniff for longer in some cases when we think we
@@ -233,6 +162,7 @@ dsm_guess_format(bool reset)
0xff, /* 8 channels (DX8) */
0x1ff, /* 9 channels (DX9, etc.) */
0x3ff, /* 10 channels (DX10) */
+ 0x1fff, /* 13 channels (DX10t) */
0x3fff /* 18 channels (DX10) */
};
unsigned votes10 = 0;
@@ -248,13 +178,13 @@ dsm_guess_format(bool reset)
}
if ((votes11 == 1) && (votes10 == 0)) {
- channel_shift = 11;
+ dsm_channel_shift = 11;
debug("DSM: 11-bit format");
return;
}
if ((votes10 == 1) && (votes11 == 0)) {
- channel_shift = 10;
+ dsm_channel_shift = 10;
debug("DSM: 10-bit format");
return;
}
@@ -264,27 +194,149 @@ dsm_guess_format(bool reset)
dsm_guess_format(true);
}
+/**
+ * Initialize the DSM receive functionality
+ *
+ * Open the UART for receiving DSM frames and configure it appropriately
+ *
+ * @param[in] device Device name of DSM UART
+ */
+int
+dsm_init(const char *device)
+{
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+ // enable power on DSM connector
+ POWER_SPEKTRUM(true);
+#endif
+
+ if (dsm_fd < 0)
+ dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
+
+ if (dsm_fd >= 0) {
+
+ struct termios t;
+
+ /* 115200bps, no parity, one stop bit */
+ tcgetattr(dsm_fd, &t);
+ cfsetspeed(&t, 115200);
+ t.c_cflag &= ~(CSTOPB | PARENB);
+ tcsetattr(dsm_fd, TCSANOW, &t);
+
+ /* initialise the decoder */
+ dsm_partial_frame_count = 0;
+ dsm_last_rx_time = hrt_absolute_time();
+
+ /* reset the format detector */
+ dsm_guess_format(true);
+
+ debug("DSM: ready");
+
+ } else {
+
+ debug("DSM: open failed");
+
+ }
+
+ return dsm_fd;
+}
+
+/**
+ * Handle DSM satellite receiver bind mode handler
+ *
+ * @param[in] cmd commands - dsm_bind_power_down, dsm_bind_power_up, dsm_bind_set_rx_out, dsm_bind_send_pulses, dsm_bind_reinit_uart
+ * @param[in] pulses Number of pulses for dsm_bind_send_pulses command
+ */
+void
+dsm_bind(uint16_t cmd, int pulses)
+{
+#if !defined(CONFIG_ARCH_BOARD_PX4IO_V1) && !defined(CONFIG_ARCH_BOARD_PX4IO_V2)
+ #warning DSM BIND NOT IMPLEMENTED ON UNKNOWN PLATFORM
+#else
+ const uint32_t usart1RxAsOutp =
+ GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN10;
+
+ if (dsm_fd < 0)
+ return;
+
+ switch (cmd) {
+
+ case dsm_bind_power_down:
+
+ /*power down DSM satellite*/
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+ POWER_RELAY1(0);
+#else /* CONFIG_ARCH_BOARD_PX4IO_V2 */
+ POWER_SPEKTRUM(0);
+#endif
+ break;
+
+ case dsm_bind_power_up:
+
+ /*power up DSM satellite*/
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+ POWER_RELAY1(1);
+#else /* CONFIG_ARCH_BOARD_PX4IO_V2 */
+ POWER_SPEKTRUM(1);
+#endif
+ dsm_guess_format(true);
+ break;
+
+ case dsm_bind_set_rx_out:
+
+ /*Set UART RX pin to active output mode*/
+ stm32_configgpio(usart1RxAsOutp);
+ break;
+
+ case dsm_bind_send_pulses:
+
+ /*Pulse RX pin a number of times*/
+ for (int i = 0; i < pulses; i++) {
+ up_udelay(25);
+ stm32_gpiowrite(usart1RxAsOutp, false);
+ up_udelay(25);
+ stm32_gpiowrite(usart1RxAsOutp, true);
+ }
+ break;
+
+ case dsm_bind_reinit_uart:
+
+ /*Restore USART RX pin to RS232 receive mode*/
+ stm32_configgpio(GPIO_USART1_RX);
+ break;
+
+ }
+#endif
+}
+
+/**
+ * Decode the entire dsm frame (all contained channels)
+ *
+ * @param[in] frame_time timestamp when this dsm frame was received. Used to detect RX loss in order to reset 10/11 bit guess.
+ * @param[out] values pointer to per channel array of decoded values
+ * @param[out] num_values pointer to number of raw channel values returned
+ * @return true=DSM frame successfully decoded, false=no update
+ */
static bool
dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
{
-
/*
- debug("DSM frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
- frame[0], frame[1], frame[2], frame[3], frame[4], frame[5], frame[6], frame[7],
- frame[8], frame[9], frame[10], frame[11], frame[12], frame[13], frame[14], frame[15]);
+ debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
+ dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7],
+ dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]);
*/
/*
* If we have lost signal for at least a second, reset the
* format guessing heuristic.
*/
- if (((frame_time - last_frame_time) > 1000000) && (channel_shift != 0))
+ if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
dsm_guess_format(true);
- /* we have received something we think is a frame */
- last_frame_time = frame_time;
+ /* we have received something we think is a dsm_frame */
+ dsm_last_frame_time = frame_time;
- /* if we don't know the frame format, update the guessing state machine */
- if (channel_shift == 0) {
+ /* if we don't know the dsm_frame format, update the guessing state machine */
+ if (dsm_channel_shift == 0) {
dsm_guess_format(false);
return false;
}
@@ -296,32 +348,46 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
* Each channel is a 16-bit unsigned value containing either a 10-
* or 11-bit channel value and a 4-bit channel number, shifted
* either 10 or 11 bits. The MSB may also be set to indicate the
- * second frame in variants of the protocol where more than
+ * second dsm_frame in variants of the protocol where more than
* seven channels are being transmitted.
*/
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
- uint8_t *dp = &frame[2 + (2 * i)];
+ uint8_t *dp = &dsm_frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
unsigned channel, value;
- if (!dsm_decode_channel(raw, channel_shift, &channel, &value))
+ if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
continue;
/* ignore channels out of range */
- if (channel >= PX4IO_INPUT_CHANNELS)
+ if (channel >= PX4IO_RC_INPUT_CHANNELS)
continue;
/* update the decoded channel count */
if (channel >= *num_values)
*num_values = channel + 1;
- /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
- if (channel_shift == 11)
- value /= 2;
+ /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
+ if (dsm_channel_shift == 10)
+ value *= 2;
- value += 998;
+ /*
+ * Spektrum scaling is special. There are these basic considerations
+ *
+ * * Midpoint is 1520 us
+ * * 100% travel channels are +- 400 us
+ *
+ * We obey the original Spektrum scaling (so a default setup will scale from
+ * 1100 - 1900 us), but we do not obey the weird 1520 us center point
+ * and instead (correctly) center the center around 1500 us. This is in order
+ * to get something useful without requiring the user to calibrate on a digital
+ * link for no reason.
+ */
+
+ /* scaled integer for decent accuracy while staying efficient */
+ value = ((((int)value - 1024) * 1000) / 1700) + 1500;
/*
* Store the decoded channel into the R/C input buffer, taking into
@@ -350,7 +416,88 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
}
/*
+ * Spektrum likes to send junk in higher channel numbers to fill
+ * their packets. We don't know about a 13 channel model in their TX
+ * lines, so if we get a channel count of 13, we'll return 12 (the last
+ * data index that is stable).
+ */
+ if (*num_values == 13)
+ *num_values = 12;
+
+ if (dsm_channel_shift == 11) {
+ /* Set the 11-bit data indicator */
+ *num_values |= 0x8000;
+ }
+
+ /*
* XXX Note that we may be in failsafe here; we need to work out how to detect that.
*/
return true;
}
+
+/**
+ * Called periodically to check for input data from the DSM UART
+ *
+ * The DSM* protocol doesn't provide any explicit framing,
+ * so we detect dsm frame boundaries by the inter-dsm frame delay.
+ * The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
+ * dsm frame transmission time is ~1.4ms.
+ * We expect to only be called when bytes arrive for processing,
+ * and if an interval of more than 5ms passes between calls,
+ * the first byte we read will be the first byte of a dsm frame.
+ * In the case where byte(s) are dropped from a dsm frame, this also
+ * provides a degree of protection. Of course, it would be better
+ * if we didn't drop bytes...
+ * Upon receiving a full dsm frame we attempt to decode it.
+ *
+ * @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
+ * @return true=decoded raw channel values updated, false=no update
+ */
+bool
+dsm_input(uint16_t *values, uint16_t *num_values)
+{
+ ssize_t ret;
+ hrt_abstime now;
+
+ /*
+ */
+ now = hrt_absolute_time();
+
+ if ((now - dsm_last_rx_time) > 5000) {
+ if (dsm_partial_frame_count > 0) {
+ dsm_frame_drops++;
+ dsm_partial_frame_count = 0;
+ }
+ }
+
+ /*
+ * Fetch bytes, but no more than we would need to complete
+ * the current dsm frame.
+ */
+ 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)
+ return false;
+
+ dsm_last_rx_time = now;
+
+ /*
+ * Add bytes to the current dsm frame
+ */
+ dsm_partial_frame_count += ret;
+
+ /*
+ * If we don't have a full dsm frame, return
+ */
+ if (dsm_partial_frame_count < DSM_FRAME_SIZE)
+ return false;
+
+ /*
+ * Great, it looks like we might have a dsm frame. Go ahead and
+ * decode it.
+ */
+ dsm_partial_frame_count = 0;
+ return dsm_decode(now, values, num_values);
+}
diff --git a/src/modules/px4iofirmware/i2c.c b/src/modules/px4iofirmware/i2c.c
index 4485daa5b..79b6546b3 100644
--- a/src/modules/px4iofirmware/i2c.c
+++ b/src/modules/px4iofirmware/i2c.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -69,6 +69,7 @@ static void i2c_rx_setup(void);
static void i2c_tx_setup(void);
static void i2c_rx_complete(void);
static void i2c_tx_complete(void);
+static void i2c_dump(void);
static DMA_HANDLE rx_dma;
static DMA_HANDLE tx_dma;
@@ -92,7 +93,7 @@ enum {
} direction;
void
-i2c_init(void)
+interface_init(void)
{
debug("i2c init");
@@ -148,12 +149,12 @@ i2c_init(void)
#endif
}
-
/*
reset the I2C bus
used to recover from lockups
*/
-void i2c_reset(void)
+void
+i2c_reset(void)
{
rCR1 |= I2C_CR1_SWRST;
rCR1 = 0;
@@ -330,7 +331,7 @@ i2c_tx_complete(void)
i2c_tx_setup();
}
-void
+static void
i2c_dump(void)
{
debug("CR1 0x%08x CR2 0x%08x", rCR1, rCR2);
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 1234e2eea..6a4429461 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -47,6 +47,7 @@
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
+#include <systemlib/pwm_limit/pwm_limit.h>
#include <systemlib/mixer/mixer.h>
extern "C" {
@@ -68,13 +69,17 @@ extern "C" {
/* current servo arm/disarm state */
static bool mixer_servos_armed = false;
+static bool should_arm = false;
+static bool should_always_enable_pwm = false;
+static volatile bool in_mixer = false;
/* selected control values and count for mixing */
enum mixer_source {
MIX_NONE,
MIX_FMU,
MIX_OVERRIDE,
- MIX_FAILSAFE
+ MIX_FAILSAFE,
+ MIX_OVERRIDE_FMU_OK
};
static mixer_source source;
@@ -85,9 +90,13 @@ static int mixer_callback(uintptr_t handle,
static MixerGroup mixer_group(mixer_callback, 0);
+/* Set the failsafe values of all mixed channels (based on zero throttle, controls centered) */
+static void mixer_set_failsafe();
+
void
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) {
@@ -95,28 +104,31 @@ mixer_tick(void)
if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
isr_debug(1, "AP RX timeout");
}
- r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK | PX4IO_P_STATUS_FLAGS_RAW_PWM);
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK);
r_status_alarms |= PX4IO_P_STATUS_ALARMS_FMU_LOST;
} else {
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
}
+ /* default to failsafe mixing */
source = MIX_FAILSAFE;
/*
* Decide which set of controls we're using.
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ||
- !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
- /* don't actually mix anything - we already have raw PWM values or
- not a valid mixer. */
+ /* do not mix if RAW_PWM mode is on and FMU is good */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
+
+ /* don't actually mix anything - we already have raw PWM values */
source = MIX_NONE;
} else {
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
/* mix from FMU controls */
@@ -125,77 +137,127 @@ mixer_tick(void)
if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
- (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_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)) {
/* if allowed, mix from RC inputs directly */
source = MIX_OVERRIDE;
+ } else if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
+ (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)) {
+
+ /* if allowed, mix from RC inputs directly up to available rc channels */
+ source = MIX_OVERRIDE_FMU_OK;
}
}
/*
+ * 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)
+ /* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ /* and FMU is armed */ && (
+ ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
+ /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
+ /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
+ /* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))
+ )
+ );
+
+ should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
+ && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
+ && (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
+
+ /*
* Run the mixers.
*/
if (source == MIX_FAILSAFE) {
/* copy failsafe values to the servo outputs */
- for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
+ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
r_page_servos[i] = r_page_servo_failsafe[i];
- } else if (source != MIX_NONE) {
+ /* safe actuators for FMU feedback */
+ r_page_actuators[i] = FLOAT_TO_REG((r_page_servos[i] - 1500) / 600.0f);
+ }
+
+
+ } else if (source != MIX_NONE && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
- float outputs[IO_SERVO_COUNT];
+ float outputs[PX4IO_SERVO_COUNT];
unsigned mixed;
/* mix */
- mixed = mixer_group.mix(&outputs[0], IO_SERVO_COUNT);
- /* scale to PWM and update the servo outputs as required */
- for (unsigned i = 0; i < mixed; i++) {
+ /* poor mans mutex */
+ in_mixer = true;
+ mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
+ in_mixer = false;
- /* save actuator values for FMU readback */
- r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
+ pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
- /* scale to servo output */
- r_page_servos[i] = (outputs[i] * 500.0f) + 1500;
+ for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
+ r_page_servos[i] = 0;
+ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
+ r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
}
- for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
- r_page_servos[i] = 0;
}
- /*
- * 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.
- */
- bool should_arm = (
- /* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
- /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
- /* there is valid input */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
- /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) &&
- /* FMU is available or FMU is not available but override is an option */
- ((r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) || (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && (r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ))
- );
+ /* set arming */
+ bool needs_to_arm = (should_arm || should_always_enable_pwm);
+
+ /* check any conditions that prevent arming */
+ if (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) {
+ needs_to_arm = false;
+ }
+ if (!should_arm && !should_always_enable_pwm) {
+ needs_to_arm = false;
+ }
- if (should_arm && !mixer_servos_armed) {
+ if (needs_to_arm && !mixer_servos_armed) {
/* need to arm, but not armed */
up_pwm_servo_arm(true);
mixer_servos_armed = true;
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED;
+ isr_debug(5, "> PWM enabled");
- } else if (!should_arm && mixer_servos_armed) {
+ } else if (!needs_to_arm && mixer_servos_armed) {
/* armed but need to disarm */
up_pwm_servo_arm(false);
mixer_servos_armed = false;
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED);
+ isr_debug(5, "> PWM disabled");
}
- if (mixer_servos_armed) {
+ if (mixer_servos_armed && should_arm) {
/* update the servo outputs. */
- for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
+ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
up_pwm_servo_set(i, r_page_servos[i]);
+
+ } else if (mixer_servos_armed && should_always_enable_pwm) {
+ /* set the disarmed servo outputs. */
+ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
+ up_pwm_servo_set(i, r_page_servo_disarmed[i]);
}
}
@@ -205,27 +267,38 @@ mixer_callback(uintptr_t handle,
uint8_t control_index,
float &control)
{
- if (control_group != 0)
+ if (control_group > 3)
return -1;
switch (source) {
case MIX_FMU:
- if (control_index < PX4IO_CONTROL_CHANNELS) {
- control = REG_TO_FLOAT(r_page_controls[control_index]);
+ if (control_index < PX4IO_CONTROL_CHANNELS && control_group < PX4IO_CONTROL_GROUPS ) {
+ control = REG_TO_FLOAT(r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)]);
break;
}
return -1;
case MIX_OVERRIDE:
- if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << control_index)) {
+ if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << CONTROL_PAGE_INDEX(control_group, control_index))) {
control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
break;
}
return -1;
+ case MIX_OVERRIDE_FMU_OK:
+ /* FMU is ok but we are in override mode, use direct rc control for the available rc channels. The remaining channels are still controlled by the fmu */
+ if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << CONTROL_PAGE_INDEX(control_group, control_index))) {
+ control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
+ break;
+ } else if (control_index < PX4IO_CONTROL_CHANNELS && control_group < PX4IO_CONTROL_GROUPS) {
+ control = REG_TO_FLOAT(r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)]);
+ break;
+ }
+ return -1;
+
case MIX_FAILSAFE:
case MIX_NONE:
- /* XXX we could allow for configuration of per-output failsafe values */
+ control = 0.0f;
return -1;
}
@@ -241,13 +314,17 @@ mixer_callback(uintptr_t handle,
static char mixer_text[256]; /* large enough for one mixer */
static unsigned mixer_text_length = 0;
-void
+int
mixer_handle_text(const void *buffer, size_t length)
{
- /* do not allow a mixer change while fully armed */
- if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
- /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
- return;
+ /* do not allow a mixer change while safety off */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
+ return 1;
+ }
+
+ /* abort if we're in the mixer */
+ if (in_mixer) {
+ return 1;
}
px4io_mixdata *msg = (px4io_mixdata *)buffer;
@@ -255,7 +332,7 @@ mixer_handle_text(const void *buffer, size_t length)
isr_debug(2, "mix txt %u", length);
if (length < sizeof(px4io_mixdata))
- return;
+ return 0;
unsigned text_length = length - sizeof(px4io_mixdata);
@@ -273,14 +350,16 @@ mixer_handle_text(const void *buffer, size_t length)
case F2I_MIXER_ACTION_APPEND:
isr_debug(2, "append %d", length);
- /* check for overflow - this is really fatal */
- /* XXX could add just what will fit & try to parse, then repeat... */
+ /* disable mixing during the update */
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
+
+ /* check for overflow - this would be really fatal */
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
- return;
+ return 0;
}
- /* append mixer text and nul-terminate */
+ /* append mixer text and nul-terminate, guard against overflow */
memcpy(&mixer_text[mixer_text_length], msg->text, text_length);
mixer_text_length += text_length;
mixer_text[mixer_text_length] = '\0';
@@ -293,8 +372,13 @@ mixer_handle_text(const void *buffer, size_t length)
/* if anything was parsed */
if (resid != mixer_text_length) {
- /* ideally, this should test resid == 0 ? */
- r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK;
+ /* only set mixer ok if no residual is left over */
+ if (resid == 0) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK;
+ } else {
+ /* not yet reached the end of the mixer, set as not ok */
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
+ }
isr_debug(2, "used %u", mixer_text_length - resid);
@@ -303,8 +387,46 @@ mixer_handle_text(const void *buffer, size_t length)
memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid);
mixer_text_length = resid;
+
+ /* update failsafe values */
+ mixer_set_failsafe();
}
break;
}
+
+ return 0;
+}
+
+static void
+mixer_set_failsafe()
+{
+ /*
+ * Check if a custom failsafe value has been written,
+ * or if the mixer is not ok and bail out.
+ */
+
+ if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ||
+ !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK))
+ return;
+
+ /* set failsafe defaults to the values for all inputs = 0 */
+ float outputs[PX4IO_SERVO_COUNT];
+ unsigned mixed;
+
+ /* mix */
+ mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
+
+ /* scale to PWM and update the servo outputs as required */
+ for (unsigned i = 0; i < mixed; i++) {
+
+ /* scale to servo output */
+ r_page_servo_failsafe[i] = (outputs[i] * 600.0f) + 1500;
+
+ }
+
+ /* disable the rest of the outputs */
+ for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
+ r_page_servo_failsafe[i] = 0;
+
}
diff --git a/src/modules/px4iofirmware/module.mk b/src/modules/px4iofirmware/module.mk
index 6379366f4..01869569f 100644
--- a/src/modules/px4iofirmware/module.mk
+++ b/src/modules/px4iofirmware/module.mk
@@ -3,17 +3,23 @@
SRCS = adc.c \
controls.c \
dsm.c \
- i2c.c \
px4io.c \
registers.c \
safety.c \
sbus.c \
../systemlib/up_cxxinitialize.c \
- ../systemlib/hx_stream.c \
../systemlib/perf_counter.c \
mixer.cpp \
../systemlib/mixer/mixer.cpp \
../systemlib/mixer/mixer_group.cpp \
../systemlib/mixer/mixer_multirotor.cpp \
../systemlib/mixer/mixer_simple.cpp \
- \ No newline at end of file
+ ../systemlib/pwm_limit/pwm_limit.c
+
+ifeq ($(BOARD),px4io-v1)
+SRCS += i2c.c
+endif
+ifeq ($(BOARD),px4io-v2)
+SRCS += serial.c \
+ ../systemlib/hx_stream.c
+endif
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index e575bd841..d48c6c529 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -36,7 +36,7 @@
/**
* @file protocol.h
*
- * PX4IO I2C interface protocol.
+ * PX4IO interface protocol.
*
* Communication is performed via writes to and reads from 16-bit virtual
* registers organised into pages of 255 registers each.
@@ -45,7 +45,7 @@
* respectively. Subsequent reads and writes increment the offset within
* the page.
*
- * Most pages are readable or writable but not both.
+ * Some pages are read- or write-only.
*
* Note that some pages may permit offset values greater than 255, which
* can only be achieved by long writes. The offset does not wrap.
@@ -62,12 +62,11 @@
* Note that the implementation of readable pages prefers registers within
* readable pages to be densely packed. Page numbers do not need to be
* packed.
+ *
+ * Definitions marked [1] are only valid on PX4IOv1 boards. Likewise,
+ * [2] denotes definitions specific to the PX4IOv2 board.
*/
-#define PX4IO_CONTROL_CHANNELS 8
-#define PX4IO_INPUT_CHANNELS 12
-#define PX4IO_RELAY_CHANNELS 4
-
/* Per C, this is safe for all 2's complement systems */
#define REG_TO_SIGNED(_reg) ((int16_t)(_reg))
#define SIGNED_TO_REG(_signed) ((uint16_t)(_signed))
@@ -75,17 +74,23 @@
#define REG_TO_FLOAT(_reg) ((float)REG_TO_SIGNED(_reg) / 10000.0f)
#define FLOAT_TO_REG(_float) SIGNED_TO_REG((int16_t)((_float) * 10000.0f))
+#define PX4IO_PROTOCOL_VERSION 4
+
+/* maximum allowable sizes on this protocol version */
+#define PX4IO_PROTOCOL_MAX_CONTROL_COUNT 8 /**< The protocol does not support more than set here, individual units might support less - see PX4IO_P_CONFIG_CONTROL_COUNT */
+
/* static configuration page */
#define PX4IO_PAGE_CONFIG 0
-#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* magic numbers TBD */
-#define PX4IO_P_CONFIG_SOFTWARE_VERSION 1 /* magic numbers TBD */
+#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* PX4IO_PROTOCOL_VERSION */
+#define PX4IO_P_CONFIG_HARDWARE_VERSION 1 /* magic numbers TBD */
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION 2 /* get this how? */
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */
#define PX4IO_P_CONFIG_CONTROL_COUNT 4 /* hardcoded max control count supported */
#define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
-#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* harcoded # of relay outputs */
+#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */
+#define PX4IO_P_CONFIG_CONTROL_GROUP_COUNT 8 /**< hardcoded # of control groups*/
/* dynamic status page */
#define PX4IO_PAGE_STATUS 1
@@ -93,7 +98,7 @@
#define PX4IO_P_STATUS_CPULOAD 1
#define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */
-#define PX4IO_P_STATUS_FLAGS_ARMED (1 << 0) /* arm-ok and locally armed */
+#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED (1 << 0) /* arm-ok and locally armed */
#define PX4IO_P_STATUS_FLAGS_OVERRIDE (1 << 1) /* in manual override */
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 2) /* RC input is valid */
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 3) /* PPM input is valid */
@@ -104,18 +109,24 @@
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
#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_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
-#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* VBatt is very close to regulator dropout */
+#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
#define PX4IO_P_STATUS_ALARMS_TEMPERATURE (1 << 1) /* board temperature is high */
-#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT (1 << 2) /* servo current limit was exceeded */
-#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT (1 << 3) /* accessory current limit was exceeded */
+#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT (1 << 2) /* [1] servo current limit was exceeded */
+#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT (1 << 3) /* [1] accessory current limit was exceeded */
#define PX4IO_P_STATUS_ALARMS_FMU_LOST (1 << 4) /* timed out waiting for controls from FMU */
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 5) /* timed out waiting for RC input */
#define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 6) /* PWM configuration or output was bad */
+#define PX4IO_P_STATUS_ALARMS_VSERVO_FAULT (1 << 7) /* [2] VServo was out of the valid range (2.5 - 5.5 V) */
-#define PX4IO_P_STATUS_VBATT 4 /* battery voltage in mV */
-#define PX4IO_P_STATUS_IBATT 5 /* battery current (raw ADC) */
+#define PX4IO_P_STATUS_VBATT 4 /* [1] battery voltage in mV */
+#define PX4IO_P_STATUS_IBATT 5 /* [1] battery current (raw ADC) */
+#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */
+#define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */
+#define PX4IO_P_STATUS_PRSSI 8 /* [2] RSSI PWM value */
/* array of post-mix actuator outputs, -10000..10000 */
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
@@ -126,7 +137,17 @@
/* array of raw RC input values, microseconds */
#define PX4IO_PAGE_RAW_RC_INPUT 4
#define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */
-#define PX4IO_P_RAW_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT channels from here */
+#define PX4IO_P_RAW_RC_FLAGS 1 /* RC detail status flags */
+#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP (1 << 0) /* single frame drop */
+#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */
+#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */
+#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */
+
+#define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
+#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
+#define PX4IO_P_RAW_FRAME_COUNT 4 /* Number of total received frames (wrapping counter) */
+#define PX4IO_P_RAW_LOST_FRAME_COUNT 5 /* Number of total dropped frames (wrapping counter) */
+#define PX4IO_P_RAW_RC_BASE 6 /* CONFIG_RC_INPUT_COUNT channels from here */
/* array of scaled RC input values, -10000..10000 */
#define PX4IO_PAGE_RC_INPUT 5
@@ -141,45 +162,99 @@
#define PX4IO_RATE_MAP_BASE 0 /* 0..CONFIG_ACTUATOR_COUNT bitmaps of PWM rate groups */
/* setup page */
-#define PX4IO_PAGE_SETUP 100
+#define PX4IO_PAGE_SETUP 50
#define PX4IO_P_SETUP_FEATURES 0
+#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT (1 << 0) /* enable S.Bus v1 output */
+#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT (1 << 1) /* enable S.Bus v2 output */
+#define PX4IO_P_SETUP_FEATURES_PWM_RSSI (1 << 2) /* enable PWM RSSI parsing */
+#define PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 3) /* enable ADC RSSI parsing */
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */
+#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
+#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */
+#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_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
#define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */
+
+#if defined(CONFIG_ARCH_BOARD_PX4IO_V1) || defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
#define PX4IO_P_SETUP_RELAYS 5 /* bitmask of relay/switch outputs, 0 = off, 1 = on */
-#define PX4IO_P_SETUP_VBATT_SCALE 6 /* battery voltage correction factor (float) */
-#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
+#define PX4IO_P_SETUP_RELAYS_POWER1 (1<<0) /* hardware rev [1] power relay 1 */
+#define PX4IO_P_SETUP_RELAYS_POWER2 (1<<1) /* hardware rev [1] power relay 2 */
+#define PX4IO_P_SETUP_RELAYS_ACC1 (1<<2) /* hardware rev [1] accessory power 1 */
+#define PX4IO_P_SETUP_RELAYS_ACC2 (1<<3) /* hardware rev [1] accessory power 2 */
+#endif
+
+#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */
+#define PX4IO_P_SETUP_VSERVO_SCALE 6 /* hardware rev [2] servo voltage correction factor (float) */
+#define PX4IO_P_SETUP_DSM 7 /* DSM bind state */
+enum { /* DSM bind states */
+ dsm_bind_power_down = 0,
+ dsm_bind_power_up,
+ dsm_bind_set_rx_out,
+ dsm_bind_send_pulses,
+ dsm_bind_reinit_uart
+};
+ /* 8 */
+#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
+
+#define PX4IO_P_SETUP_REBOOT_BL 10 /* reboot IO into bootloader */
+#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
+
+#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
/* autopilot control values, -10000..10000 */
-#define PX4IO_PAGE_CONTROLS 101 /* 0..CONFIG_CONTROL_COUNT */
+#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
+#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+#define PX4IO_P_CONTROLS_GROUP_3 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
+
+#define PX4IO_P_CONTROLS_GROUP_VALID 64
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0 (1 << 0) /* group 0 is valid / received */
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1 (1 << 1) /* group 1 is valid / received */
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2 (1 << 2) /* group 2 is valid / received */
+#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3 (1 << 3) /* group 3 is valid / received */
/* raw text load to the mixer parser - ignores offset */
-#define PX4IO_PAGE_MIXERLOAD 102
+#define PX4IO_PAGE_MIXERLOAD 52
/* R/C channel config */
-#define PX4IO_PAGE_RC_CONFIG 103 /* R/C input configuration */
-#define PX4IO_P_RC_CONFIG_MIN 0 /* lowest input value */
-#define PX4IO_P_RC_CONFIG_CENTER 1 /* center input value */
-#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_OPTIONS 5 /* channel options bitmask */
+#define PX4IO_PAGE_RC_CONFIG 53 /**< R/C input configuration */
+#define PX4IO_P_RC_CONFIG_MIN 0 /**< lowest input value */
+#define PX4IO_P_RC_CONFIG_CENTER 1 /**< center input value */
+#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_OPTIONS 5 /**< channel options bitmask */
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0)
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
-#define PX4IO_P_RC_CONFIG_STRIDE 6 /* spacing between channel config data */
+#define PX4IO_P_RC_CONFIG_STRIDE 6 /**< spacing between channel config data */
/* PWM output - overrides mixer */
-#define PX4IO_PAGE_DIRECT_PWM 104 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_DIRECT_PWM 54 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
/* PWM failsafe values - zero disables the output */
-#define PX4IO_PAGE_FAILSAFE_PWM 105 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+#define PX4IO_PAGE_FAILSAFE_PWM 55 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
+
+/* Debug and test page - not used in normal operation */
+#define PX4IO_PAGE_TEST 127
+#define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */
+
+/* PWM minimum values for certain ESCs */
+#define PX4IO_PAGE_CONTROL_MIN_PWM 106 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
+
+/* PWM maximum values for certain ESCs */
+#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
+
+/* PWM disarmed values that are active, even when SAFETY_SAFE */
+#define PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
/**
* As-needed mixer data upload.
@@ -200,3 +275,81 @@ struct px4io_mixdata {
};
#pragma pack(pop)
+/**
+ * Serial protocol encapsulation.
+ */
+
+#define PKT_MAX_REGS 32 // by agreement w/FMU
+
+#pragma pack(push, 1)
+struct IOPacket {
+ uint8_t count_code;
+ uint8_t crc;
+ uint8_t page;
+ uint8_t offset;
+ uint16_t regs[PKT_MAX_REGS];
+};
+#pragma pack(pop)
+
+#define PKT_CODE_READ 0x00 /* FMU->IO read transaction */
+#define PKT_CODE_WRITE 0x40 /* FMU->IO write transaction */
+#define PKT_CODE_SUCCESS 0x00 /* IO->FMU success reply */
+#define PKT_CODE_CORRUPT 0x40 /* IO->FMU bad packet reply */
+#define PKT_CODE_ERROR 0x80 /* IO->FMU register op error reply */
+
+#define PKT_CODE_MASK 0xc0
+#define PKT_COUNT_MASK 0x3f
+
+#define PKT_COUNT(_p) ((_p).count_code & PKT_COUNT_MASK)
+#define PKT_CODE(_p) ((_p).count_code & PKT_CODE_MASK)
+#define PKT_SIZE(_p) ((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p)))
+
+static const uint8_t crc8_tab[256] __attribute__((unused)) =
+{
+ 0x00, 0x07, 0x0E, 0x09, 0x1C, 0x1B, 0x12, 0x15,
+ 0x38, 0x3F, 0x36, 0x31, 0x24, 0x23, 0x2A, 0x2D,
+ 0x70, 0x77, 0x7E, 0x79, 0x6C, 0x6B, 0x62, 0x65,
+ 0x48, 0x4F, 0x46, 0x41, 0x54, 0x53, 0x5A, 0x5D,
+ 0xE0, 0xE7, 0xEE, 0xE9, 0xFC, 0xFB, 0xF2, 0xF5,
+ 0xD8, 0xDF, 0xD6, 0xD1, 0xC4, 0xC3, 0xCA, 0xCD,
+ 0x90, 0x97, 0x9E, 0x99, 0x8C, 0x8B, 0x82, 0x85,
+ 0xA8, 0xAF, 0xA6, 0xA1, 0xB4, 0xB3, 0xBA, 0xBD,
+ 0xC7, 0xC0, 0xC9, 0xCE, 0xDB, 0xDC, 0xD5, 0xD2,
+ 0xFF, 0xF8, 0xF1, 0xF6, 0xE3, 0xE4, 0xED, 0xEA,
+ 0xB7, 0xB0, 0xB9, 0xBE, 0xAB, 0xAC, 0xA5, 0xA2,
+ 0x8F, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9D, 0x9A,
+ 0x27, 0x20, 0x29, 0x2E, 0x3B, 0x3C, 0x35, 0x32,
+ 0x1F, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0D, 0x0A,
+ 0x57, 0x50, 0x59, 0x5E, 0x4B, 0x4C, 0x45, 0x42,
+ 0x6F, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7D, 0x7A,
+ 0x89, 0x8E, 0x87, 0x80, 0x95, 0x92, 0x9B, 0x9C,
+ 0xB1, 0xB6, 0xBF, 0xB8, 0xAD, 0xAA, 0xA3, 0xA4,
+ 0xF9, 0xFE, 0xF7, 0xF0, 0xE5, 0xE2, 0xEB, 0xEC,
+ 0xC1, 0xC6, 0xCF, 0xC8, 0xDD, 0xDA, 0xD3, 0xD4,
+ 0x69, 0x6E, 0x67, 0x60, 0x75, 0x72, 0x7B, 0x7C,
+ 0x51, 0x56, 0x5F, 0x58, 0x4D, 0x4A, 0x43, 0x44,
+ 0x19, 0x1E, 0x17, 0x10, 0x05, 0x02, 0x0B, 0x0C,
+ 0x21, 0x26, 0x2F, 0x28, 0x3D, 0x3A, 0x33, 0x34,
+ 0x4E, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5C, 0x5B,
+ 0x76, 0x71, 0x78, 0x7F, 0x6A, 0x6D, 0x64, 0x63,
+ 0x3E, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2C, 0x2B,
+ 0x06, 0x01, 0x08, 0x0F, 0x1A, 0x1D, 0x14, 0x13,
+ 0xAE, 0xA9, 0xA0, 0xA7, 0xB2, 0xB5, 0xBC, 0xBB,
+ 0x96, 0x91, 0x98, 0x9F, 0x8A, 0x8D, 0x84, 0x83,
+ 0xDE, 0xD9, 0xD0, 0xD7, 0xC2, 0xC5, 0xCC, 0xCB,
+ 0xE6, 0xE1, 0xE8, 0xEF, 0xFA, 0xFD, 0xF4, 0xF3
+};
+
+static uint8_t crc_packet(struct IOPacket *pkt) __attribute__((unused));
+static uint8_t
+crc_packet(struct IOPacket *pkt)
+{
+ uint8_t *end = (uint8_t *)(&pkt->regs[PKT_COUNT(*pkt)]);
+ uint8_t *p = (uint8_t *)pkt;
+ uint8_t c = 0;
+
+ while (p < end)
+ c = crc8_tab[c ^ *(p++)];
+
+ return c;
+}
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index bc8dfc116..d4c25911e 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -45,11 +45,13 @@
#include <string.h>
#include <poll.h>
#include <signal.h>
+#include <crc32.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
#include <systemlib/perf_counter.h>
+#include <systemlib/pwm_limit/pwm_limit.h>
#include <stm32_uart.h>
@@ -64,10 +66,7 @@ struct sys_state_s system_state;
static struct hrt_call serial_dma_call;
-#ifdef CONFIG_STM32_I2C1
-/* store i2c reset count XXX this should be a register, together with other error counters */
-volatile uint32_t i2c_loop_resets = 0;
-#endif
+pwm_limit_t pwm_limit;
/*
* a set of debug buffers to allow us to send debug information from ISRs
@@ -119,6 +118,48 @@ show_debug_messages(void)
}
}
+static void
+heartbeat_blink(void)
+{
+ static bool heartbeat = false;
+ LED_BLUE(heartbeat = !heartbeat);
+}
+
+static uint64_t reboot_time;
+
+/**
+ schedule a reboot in time_delta_usec microseconds
+ */
+void schedule_reboot(uint32_t time_delta_usec)
+{
+ reboot_time = hrt_absolute_time() + time_delta_usec;
+}
+
+/**
+ check for a scheduled reboot
+ */
+static void check_reboot(void)
+{
+ if (reboot_time != 0 && hrt_absolute_time() > reboot_time) {
+ up_systemreset();
+ }
+}
+
+static void
+calculate_fw_crc(void)
+{
+#define APP_SIZE_MAX 0xf000
+#define APP_LOAD_ADDRESS 0x08001000
+ // compute CRC of the current firmware
+ uint32_t sum = 0;
+ for (unsigned p = 0; p < APP_SIZE_MAX; p += 4) {
+ uint32_t bytes = *(uint32_t *)(p + APP_LOAD_ADDRESS);
+ sum = crc32part((uint8_t *)&bytes, sizeof(bytes), sum);
+ }
+ r_page_setup[PX4IO_P_SETUP_CRC] = sum & 0xFFFF;
+ r_page_setup[PX4IO_P_SETUP_CRC+1] = sum >> 16;
+}
+
int
user_start(int argc, char *argv[])
{
@@ -131,6 +172,9 @@ user_start(int argc, char *argv[])
/* configure the high-resolution time/callout interface */
hrt_init();
+ /* calculate our fw CRC so FMU can decide if we need to update */
+ calculate_fw_crc();
+
/*
* Poll at 1ms intervals for received bytes that have not triggered
* a DMA event.
@@ -147,8 +191,15 @@ user_start(int argc, char *argv[])
LED_BLUE(false);
LED_SAFETY(false);
- /* turn on servo power */
+ /* turn on servo power (if supported) */
+#ifdef POWER_SERVO
POWER_SERVO(true);
+#endif
+
+ /* turn off S.Bus out (if supported) */
+#ifdef ENABLE_SBUS_OUT
+ ENABLE_SBUS_OUT(false);
+#endif
/* start the safety switch handler */
safety_init();
@@ -159,10 +210,11 @@ user_start(int argc, char *argv[])
/* initialise the control inputs */
controls_init();
-#ifdef CONFIG_STM32_I2C1
- /* start the i2c handler */
- i2c_init();
-#endif
+ /* set up the ADC */
+ adc_init();
+
+ /* start the FMU interface */
+ interface_init();
/* add a performance counter for mixing */
perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix");
@@ -176,30 +228,51 @@ user_start(int argc, char *argv[])
struct mallinfo minfo = mallinfo();
lowsyslog("MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks);
-#if 0
- /* not enough memory, lock down */
- if (minfo.mxordblk < 500) {
+ /* initialize PWM limit lib */
+ pwm_limit_init(&pwm_limit);
+
+ /*
+ * P O L I C E L I G H T S
+ *
+ * Not enough memory, lock down.
+ *
+ * We might need to allocate mixers later, and this will
+ * ensure that a developer doing a change will notice
+ * that he just burned the remaining RAM with static
+ * allocations. We don't want him to be able to
+ * get past that point. This needs to be clearly
+ * documented in the dev guide.
+ *
+ */
+ if (minfo.mxordblk < 600) {
+
lowsyslog("ERR: not enough MEM");
bool phase = false;
- if (phase) {
- LED_AMBER(true);
- LED_BLUE(false);
- } else {
- LED_AMBER(false);
- LED_BLUE(true);
- }
+ while (true) {
- phase = !phase;
- usleep(300000);
+ if (phase) {
+ LED_AMBER(true);
+ LED_BLUE(false);
+ } else {
+ LED_AMBER(false);
+ LED_BLUE(true);
+ }
+ up_udelay(250000);
+
+ phase = !phase;
+ }
}
-#endif
+
+ /* Start the failsafe led init */
+ failsafe_led_init();
/*
* Run everything in a tight loop.
*/
uint64_t last_debug_time = 0;
+ uint64_t last_heartbeat_time = 0;
for (;;) {
/* track the rate at which the loop is running */
@@ -215,20 +288,28 @@ user_start(int argc, char *argv[])
controls_tick();
perf_end(controls_perf);
- /* check for debug activity */
+ if ((hrt_absolute_time() - last_heartbeat_time) > 250*1000) {
+ last_heartbeat_time = hrt_absolute_time();
+ heartbeat_blink();
+ }
+
+ check_reboot();
+
+ /* check for debug activity (default: none) */
show_debug_messages();
- /* post debug state at ~1Hz */
+ /* post debug state at ~1Hz - this is via an auxiliary serial port
+ * DEFAULTS TO OFF!
+ */
if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) {
struct mallinfo minfo = mallinfo();
- isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x r=%u m=%u",
+ isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x m=%u",
(unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG],
(unsigned)r_status_flags,
(unsigned)r_setup_arming,
(unsigned)r_setup_features,
- (unsigned)i2c_loop_resets,
(unsigned)minfo.mxordblk);
last_debug_time = hrt_absolute_time();
}
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 272cdb7bf..bb224f388 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -42,15 +42,20 @@
#include <stdbool.h>
#include <stdint.h>
-#include <drivers/boards/px4io/px4io_internal.h>
+#include <board_config.h>
#include "protocol.h"
+#include <systemlib/pwm_limit/pwm_limit.h>
+
/*
* Constants and limits.
*/
-#define MAX_CONTROL_CHANNELS 12
-#define IO_SERVO_COUNT 8
+#define PX4IO_SERVO_COUNT 8
+#define PX4IO_CONTROL_CHANNELS 8
+#define PX4IO_CONTROL_GROUPS 2
+#define PX4IO_RC_INPUT_CHANNELS 18
+#define PX4IO_RC_MAPPED_CONTROL_CHANNELS 8 /**< This is the maximum number of channels mapped/used */
/*
* Debug logging
@@ -77,6 +82,9 @@ extern volatile uint16_t r_page_setup[]; /* PX4IO_PAGE_SETUP */
extern volatile uint16_t r_page_controls[]; /* PX4IO_PAGE_CONTROLS */
extern uint16_t r_page_rc_input_config[]; /* PX4IO_PAGE_RC_INPUT_CONFIG */
extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
+extern uint16_t r_page_servo_control_min[]; /* PX4IO_PAGE_CONTROL_MIN_PWM */
+extern uint16_t r_page_servo_control_max[]; /* PX4IO_PAGE_CONTROL_MAX_PWM */
+extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */
/*
* Register aliases.
@@ -88,15 +96,18 @@ extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
#define r_raw_rc_count r_page_raw_rc_input[PX4IO_P_RAW_RC_COUNT]
#define r_raw_rc_values (&r_page_raw_rc_input[PX4IO_P_RAW_RC_BASE])
+#define r_raw_rc_flags r_page_raw_rc_input[PX4IO_P_RAW_RC_FLAGS]
#define r_rc_valid r_page_rc_input[PX4IO_P_RC_VALID]
-#define r_rc_values (&r_page_rc_input[PX4IO_P_RAW_RC_BASE])
+#define r_rc_values (&r_page_rc_input[PX4IO_P_RC_BASE])
#define r_setup_features r_page_setup[PX4IO_P_SETUP_FEATURES]
#define r_setup_arming r_page_setup[PX4IO_P_SETUP_ARMING]
#define r_setup_pwm_rates r_page_setup[PX4IO_P_SETUP_PWM_RATES]
#define r_setup_pwm_defaultrate r_page_setup[PX4IO_P_SETUP_PWM_DEFAULTRATE]
#define r_setup_pwm_altrate r_page_setup[PX4IO_P_SETUP_PWM_ALTRATE]
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
#define r_setup_relays r_page_setup[PX4IO_P_SETUP_RELAYS]
+#endif
#define r_control_values (&r_page_controls[0])
@@ -105,7 +116,8 @@ extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
*/
struct sys_state_s {
- volatile uint64_t rc_channels_timestamp;
+ volatile uint64_t rc_channels_timestamp_received;
+ volatile uint64_t rc_channels_timestamp_valid;
/**
* Last FMU receive time, in microseconds since system boot
@@ -117,56 +129,75 @@ struct sys_state_s {
extern struct sys_state_s system_state;
/*
+ * PWM limit structure
+ */
+extern pwm_limit_t pwm_limit;
+
+/*
* GPIO handling.
*/
-#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_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))
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+
+# define PX4IO_RELAY_CHANNELS 4
+# define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
+# define POWER_ACC1(_s) stm32_gpiowrite(GPIO_ACC1_PWR_EN, (_s))
+# define POWER_ACC2(_s) stm32_gpiowrite(GPIO_ACC2_PWR_EN, (_s))
+# define POWER_RELAY1(_s) stm32_gpiowrite(GPIO_RELAY1_EN, (_s))
+# define POWER_RELAY2(_s) stm32_gpiowrite(GPIO_RELAY2_EN, (_s))
+
+# define OVERCURRENT_ACC (!stm32_gpioread(GPIO_ACC_OC_DETECT))
+# define OVERCURRENT_SERVO (!stm32_gpioread(GPIO_SERVO_OC_DETECT))
+
+# define PX4IO_ADC_CHANNEL_COUNT 2
+# define ADC_VBATT 4
+# define ADC_IN5 5
-#define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
-#ifdef GPIO_ACC1_PWR_EN
- #define POWER_ACC1(_s) stm32_gpiowrite(GPIO_ACC1_PWR_EN, (_s))
-#endif
-#ifdef GPIO_ACC2_PWR_EN
- #define POWER_ACC2(_s) stm32_gpiowrite(GPIO_ACC2_PWR_EN, (_s))
-#endif
-#ifdef GPIO_RELAY1_EN
- #define POWER_RELAY1(_s) stm32_gpiowrite(GPIO_RELAY1_EN, (_s))
#endif
-#ifdef GPIO_RELAY2_EN
- #define POWER_RELAY2(_s) stm32_gpiowrite(GPIO_RELAY2_EN, (_s))
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+
+# define PX4IO_RELAY_CHANNELS 0
+# define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s))
+# define ENABLE_SBUS_OUT(_s) stm32_gpiowrite(GPIO_SBUS_OENABLE, !(_s))
+
+# define VDD_SERVO_FAULT (!stm32_gpioread(GPIO_SERVO_FAULT_DETECT))
+
+# define PX4IO_ADC_CHANNEL_COUNT 2
+# define ADC_VSERVO 4
+# define ADC_RSSI 5
+
#endif
-#define OVERCURRENT_ACC (!stm32_gpioread(GPIO_ACC_OC_DETECT))
-#define OVERCURRENT_SERVO (!stm32_gpioread(GPIO_SERVO_OC_DETECT))
#define BUTTON_SAFETY stm32_gpioread(GPIO_BTN_SAFETY)
-#define ADC_VBATT 4
-#define ADC_IN5 5
-#define ADC_CHANNEL_COUNT 2
+#define CONTROL_PAGE_INDEX(_group, _channel) (_group * PX4IO_CONTROL_CHANNELS + _channel)
/*
* Mixer
*/
extern void mixer_tick(void);
-extern void mixer_handle_text(const void *buffer, size_t length);
+extern int mixer_handle_text(const void *buffer, size_t length);
/**
* Safety switch/LED.
*/
extern void safety_init(void);
+extern void failsafe_led_init(void);
-#ifdef CONFIG_STM32_I2C1
/**
* FMU communications
*/
-extern void i2c_init(void);
-#endif
+extern void interface_init(void);
+extern void interface_tick(void);
/**
* Register space
*/
-extern void registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
+extern int registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
extern int registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values);
/**
@@ -184,16 +215,16 @@ 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 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);
+extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
/** global debug level for isr_debug() */
extern volatile uint8_t debug_level;
-/* send a debug message to the console */
-extern void isr_debug(uint8_t level, const char *fmt, ...);
+/** send a debug message to the console */
+extern void isr_debug(uint8_t level, const char *fmt, ...);
+
+/** schedule a reboot */
+extern void schedule_reboot(uint32_t time_delta_usec);
-#ifdef CONFIG_STM32_I2C1
-void i2c_dump(void);
-void i2c_reset(void);
-#endif
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 9698a0f2f..97d25bbfa 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -41,8 +41,12 @@
#include <stdbool.h>
#include <stdlib.h>
+#include <string.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_pwm_output.h>
+#include <systemlib/systemlib.h>
+#include <stm32_pwr.h>
#include "px4io.h"
#include "protocol.h"
@@ -56,14 +60,18 @@ static void pwm_configure_rates(uint16_t map, uint16_t defaultrate, uint16_t alt
* Static configuration parameters.
*/
static const uint16_t r_page_config[] = {
- [PX4IO_P_CONFIG_PROTOCOL_VERSION] = 1, /* XXX hardcoded magic number */
- [PX4IO_P_CONFIG_SOFTWARE_VERSION] = 1, /* XXX hardcoded magic number */
+ [PX4IO_P_CONFIG_PROTOCOL_VERSION] = PX4IO_PROTOCOL_VERSION,
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+ [PX4IO_P_CONFIG_HARDWARE_VERSION] = 2,
+#else
+ [PX4IO_P_CONFIG_HARDWARE_VERSION] = 1,
+#endif
[PX4IO_P_CONFIG_BOOTLOADER_VERSION] = 3, /* XXX hardcoded magic number */
[PX4IO_P_CONFIG_MAX_TRANSFER] = 64, /* XXX hardcoded magic number */
[PX4IO_P_CONFIG_CONTROL_COUNT] = PX4IO_CONTROL_CHANNELS,
- [PX4IO_P_CONFIG_ACTUATOR_COUNT] = IO_SERVO_COUNT,
- [PX4IO_P_CONFIG_RC_INPUT_COUNT] = MAX_CONTROL_CHANNELS,
- [PX4IO_P_CONFIG_ADC_INPUT_COUNT] = ADC_CHANNEL_COUNT,
+ [PX4IO_P_CONFIG_ACTUATOR_COUNT] = PX4IO_SERVO_COUNT,
+ [PX4IO_P_CONFIG_RC_INPUT_COUNT] = PX4IO_RC_INPUT_CHANNELS,
+ [PX4IO_P_CONFIG_ADC_INPUT_COUNT] = PX4IO_ADC_CHANNEL_COUNT,
[PX4IO_P_CONFIG_RELAY_COUNT] = PX4IO_RELAY_CHANNELS,
};
@@ -78,7 +86,10 @@ uint16_t r_page_status[] = {
[PX4IO_P_STATUS_FLAGS] = 0,
[PX4IO_P_STATUS_ALARMS] = 0,
[PX4IO_P_STATUS_VBATT] = 0,
- [PX4IO_P_STATUS_IBATT] = 0
+ [PX4IO_P_STATUS_IBATT] = 0,
+ [PX4IO_P_STATUS_VSERVO] = 0,
+ [PX4IO_P_STATUS_VRSSI] = 0,
+ [PX4IO_P_STATUS_PRSSI] = 0,
};
/**
@@ -86,14 +97,14 @@ uint16_t r_page_status[] = {
*
* Post-mixed actuator values.
*/
-uint16_t r_page_actuators[IO_SERVO_COUNT];
+uint16_t r_page_actuators[PX4IO_SERVO_COUNT];
/**
* PAGE 3
*
* Servo PWM values
*/
-uint16_t r_page_servos[IO_SERVO_COUNT];
+uint16_t r_page_servos[PX4IO_SERVO_COUNT];
/**
* PAGE 4
@@ -103,7 +114,13 @@ uint16_t r_page_servos[IO_SERVO_COUNT];
uint16_t r_page_raw_rc_input[] =
{
[PX4IO_P_RAW_RC_COUNT] = 0,
- [PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + MAX_CONTROL_CHANNELS)] = 0
+ [PX4IO_P_RAW_RC_FLAGS] = 0,
+ [PX4IO_P_RAW_RC_NRSSI] = 0,
+ [PX4IO_P_RAW_RC_DATA] = 0,
+ [PX4IO_P_RAW_FRAME_COUNT] = 0,
+ [PX4IO_P_RAW_LOST_FRAME_COUNT] = 0,
+ [PX4IO_P_RAW_RC_DATA] = 0,
+ [PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_RC_INPUT_CHANNELS)] = 0
};
/**
@@ -113,7 +130,7 @@ uint16_t r_page_raw_rc_input[] =
*/
uint16_t r_page_rc_input[] = {
[PX4IO_P_RC_VALID] = 0,
- [PX4IO_P_RC_BASE ... (PX4IO_P_RC_BASE + MAX_CONTROL_CHANNELS)] = 0
+ [PX4IO_P_RC_BASE ... (PX4IO_P_RC_BASE + PX4IO_RC_MAPPED_CONTROL_CHANNELS)] = 0
};
/**
@@ -131,22 +148,46 @@ uint16_t r_page_scratch[32];
*/
volatile uint16_t r_page_setup[] =
{
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+ /* default to RSSI ADC functionality */
+ [PX4IO_P_SETUP_FEATURES] = PX4IO_P_SETUP_FEATURES_ADC_RSSI,
+#else
[PX4IO_P_SETUP_FEATURES] = 0,
+#endif
[PX4IO_P_SETUP_ARMING] = 0,
[PX4IO_P_SETUP_PWM_RATES] = 0,
[PX4IO_P_SETUP_PWM_DEFAULTRATE] = 50,
[PX4IO_P_SETUP_PWM_ALTRATE] = 200,
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
[PX4IO_P_SETUP_RELAYS] = 0,
+#endif
+#ifdef ADC_VSERVO
+ [PX4IO_P_SETUP_VSERVO_SCALE] = 10000,
+#else
[PX4IO_P_SETUP_VBATT_SCALE] = 10000,
+#endif
[PX4IO_P_SETUP_SET_DEBUG] = 0,
+ [PX4IO_P_SETUP_REBOOT_BL] = 0,
+ [PX4IO_P_SETUP_CRC ... (PX4IO_P_SETUP_CRC+1)] = 0,
};
-#define PX4IO_P_SETUP_FEATURES_VALID (0)
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+#define PX4IO_P_SETUP_FEATURES_VALID (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | \
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT | \
+ PX4IO_P_SETUP_FEATURES_ADC_RSSI | \
+ PX4IO_P_SETUP_FEATURES_PWM_RSSI)
+#else
+#define PX4IO_P_SETUP_FEATURES_VALID 0
+#endif
#define PX4IO_P_SETUP_ARMING_VALID (PX4IO_P_SETUP_ARMING_FMU_ARMED | \
PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK | \
PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK | \
- PX4IO_P_SETUP_ARMING_IO_ARM_OK)
-#define PX4IO_P_SETUP_RATES_VALID ((1 << IO_SERVO_COUNT) - 1)
+ PX4IO_P_SETUP_ARMING_IO_ARM_OK | \
+ PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM | \
+ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE | \
+ PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \
+ PX4IO_P_SETUP_ARMING_LOCKDOWN)
+#define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1)
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
/**
@@ -154,7 +195,7 @@ volatile uint16_t r_page_setup[] =
*
* Control values from the FMU.
*/
-volatile uint16_t r_page_controls[PX4IO_CONTROL_CHANNELS];
+volatile uint16_t r_page_controls[PX4IO_CONTROL_GROUPS * PX4IO_CONTROL_CHANNELS];
/*
* PAGE 102 does not have a buffer.
@@ -165,7 +206,7 @@ volatile uint16_t r_page_controls[PX4IO_CONTROL_CHANNELS];
*
* R/C channel input configuration.
*/
-uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE];
+uint16_t r_page_rc_input_config[PX4IO_RC_INPUT_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE];
/* valid options */
#define PX4IO_P_RC_CONFIG_OPTIONS_VALID (PX4IO_P_RC_CONFIG_OPTIONS_REVERSE | PX4IO_P_RC_CONFIG_OPTIONS_ENABLED)
@@ -178,10 +219,36 @@ uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE
* PAGE 105
*
* Failsafe servo PWM values
+ *
+ * Disable pulses as default.
*/
-uint16_t r_page_servo_failsafe[IO_SERVO_COUNT];
+uint16_t r_page_servo_failsafe[PX4IO_SERVO_COUNT] = { 0, 0, 0, 0, 0, 0, 0, 0 };
-void
+/**
+ * PAGE 106
+ *
+ * minimum PWM values when armed
+ *
+ */
+uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN };
+
+/**
+ * PAGE 107
+ *
+ * maximum PWM values when armed
+ *
+ */
+uint16_t r_page_servo_control_max[PX4IO_SERVO_COUNT] = { PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX };
+
+/**
+ * PAGE 108
+ *
+ * disarmed PWM values for difficult ESCs
+ *
+ */
+uint16_t r_page_servo_disarmed[PX4IO_SERVO_COUNT] = { 0, 0, 0, 0, 0, 0, 0, 0 };
+
+int
registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
{
@@ -191,7 +258,7 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
case PX4IO_PAGE_CONTROLS:
/* copy channel data */
- while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
+ while ((offset < PX4IO_CONTROL_GROUPS * PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
/* XXX range-check value? */
r_page_controls[offset] = *values;
@@ -230,20 +297,112 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
case PX4IO_PAGE_FAILSAFE_PWM:
/* copy channel data */
- while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
+ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0) {
+ /* ignore 0 */
+ } else if (*values < PWM_LOWEST_MIN) {
+ r_page_servo_failsafe[offset] = PWM_LOWEST_MIN;
+ } else if (*values > PWM_HIGHEST_MAX) {
+ r_page_servo_failsafe[offset] = PWM_HIGHEST_MAX;
+ } else {
+ r_page_servo_failsafe[offset] = *values;
+ }
- /* XXX range-check value? */
- r_page_servo_failsafe[offset] = *values;
+ /* flag the failsafe values as custom */
+ r_setup_arming |= PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM;
+
+ offset++;
+ num_values--;
+ values++;
+ }
+ break;
+
+ case PX4IO_PAGE_CONTROL_MIN_PWM:
+
+ /* copy channel data */
+ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0) {
+ /* ignore 0 */
+ } else if (*values > PWM_HIGHEST_MIN) {
+ r_page_servo_control_min[offset] = PWM_HIGHEST_MIN;
+ } else if (*values < PWM_LOWEST_MIN) {
+ r_page_servo_control_min[offset] = PWM_LOWEST_MIN;
+ } else {
+ r_page_servo_control_min[offset] = *values;
+ }
offset++;
num_values--;
values++;
}
break;
+
+ case PX4IO_PAGE_CONTROL_MAX_PWM:
+
+ /* copy channel data */
+ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0) {
+ /* ignore 0 */
+ } else if (*values > PWM_HIGHEST_MAX) {
+ r_page_servo_control_max[offset] = PWM_HIGHEST_MAX;
+ } else if (*values < PWM_LOWEST_MAX) {
+ r_page_servo_control_max[offset] = PWM_LOWEST_MAX;
+ } else {
+ r_page_servo_control_max[offset] = *values;
+ }
+
+ offset++;
+ num_values--;
+ values++;
+ }
+ break;
+
+ case PX4IO_PAGE_DISARMED_PWM:
+ {
+ /* flag for all outputs */
+ bool all_disarmed_off = true;
+
+ /* copy channel data */
+ while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
+
+ if (*values == 0) {
+ /* 0 means disabling always PWM */
+ r_page_servo_disarmed[offset] = 0;
+ } else if (*values < PWM_LOWEST_MIN) {
+ r_page_servo_disarmed[offset] = PWM_LOWEST_MIN;
+ all_disarmed_off = false;
+ } else if (*values > PWM_HIGHEST_MAX) {
+ r_page_servo_disarmed[offset] = PWM_HIGHEST_MAX;
+ all_disarmed_off = false;
+ } else {
+ r_page_servo_disarmed[offset] = *values;
+ all_disarmed_off = false;
+ }
+
+ offset++;
+ num_values--;
+ values++;
+ }
+
+ if (all_disarmed_off) {
+ /* disable PWM output if disarmed */
+ r_setup_arming &= ~(PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE);
+ } else {
+ /* enable PWM output always */
+ r_setup_arming |= PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE;
+ }
+ }
+ break;
/* handle text going to the mixer parser */
case PX4IO_PAGE_MIXERLOAD:
- mixer_handle_text(values, num_values * sizeof(*values));
+ if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
+ return mixer_handle_text(values, num_values * sizeof(*values));
+ }
break;
default:
@@ -254,11 +413,13 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
/* iterate individual registers, set each in turn */
while (num_values--) {
if (registers_set_one(page, offset, *values))
- break;
+ return -1;
offset++;
values++;
}
+ break;
}
+ return 0;
}
static int
@@ -294,9 +455,35 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
case PX4IO_P_SETUP_FEATURES:
value &= PX4IO_P_SETUP_FEATURES_VALID;
- r_setup_features = value;
- /* no implemented feature selection at this point */
+ /* some of the options conflict - give S.BUS out precedence, then ADC RSSI, then PWM RSSI */
+
+ /* switch S.Bus output pin as needed */
+ #ifdef ENABLE_SBUS_OUT
+ ENABLE_SBUS_OUT(value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT));
+
+ /* disable the conflicting options */
+ if (value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI | PX4IO_P_SETUP_FEATURES_ADC_RSSI);
+ }
+ #endif
+
+ /* disable the conflicting options with ADC RSSI */
+ if (value & (PX4IO_P_SETUP_FEATURES_ADC_RSSI)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI |
+ PX4IO_P_SETUP_FEATURES_SBUS1_OUT |
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT);
+ }
+
+ /* disable the conflicting options with PWM RSSI (without effect here, but for completeness) */
+ if (value & (PX4IO_P_SETUP_FEATURES_PWM_RSSI)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_ADC_RSSI |
+ PX4IO_P_SETUP_FEATURES_SBUS1_OUT |
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT);
+ }
+
+ /* apply changes */
+ r_setup_features = value;
break;
@@ -311,8 +498,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
* so that an in-air reset of FMU can not lead to a
* lockup of the IO arming state.
*/
- if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && !(value & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
+
+ if (value & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_INIT_OK;
}
r_setup_arming = value;
@@ -340,13 +528,19 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
pwm_configure_rates(r_setup_pwm_rates, r_setup_pwm_defaultrate, value);
break;
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
case PX4IO_P_SETUP_RELAYS:
value &= PX4IO_P_SETUP_RELAYS_VALID;
r_setup_relays = value;
- POWER_RELAY1(value & (1 << 0) ? 1 : 0);
- POWER_RELAY2(value & (1 << 1) ? 1 : 0);
- POWER_ACC1(value & (1 << 2) ? 1 : 0);
- POWER_ACC2(value & (1 << 3) ? 1 : 0);
+ POWER_RELAY1((value & PX4IO_P_SETUP_RELAYS_POWER1) ? 1 : 0);
+ POWER_RELAY2((value & PX4IO_P_SETUP_RELAYS_POWER2) ? 1 : 0);
+ POWER_ACC1((value & PX4IO_P_SETUP_RELAYS_ACC1) ? 1 : 0);
+ POWER_ACC2((value & PX4IO_P_SETUP_RELAYS_ACC2) ? 1 : 0);
+ break;
+#endif
+
+ case PX4IO_P_SETUP_VBATT_SCALE:
+ r_page_setup[PX4IO_P_SETUP_VBATT_SCALE] = value;
break;
case PX4IO_P_SETUP_SET_DEBUG:
@@ -354,6 +548,27 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
isr_debug(0, "set debug %u\n", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG]);
break;
+ case PX4IO_P_SETUP_REBOOT_BL:
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
+ // don't allow reboot while armed
+ break;
+ }
+
+ // check the magic value
+ if (value != PX4IO_REBOOT_BL_MAGIC)
+ break;
+
+ // we schedule a reboot rather than rebooting
+ // immediately to allow the IO board to ACK
+ // the reboot command
+ schedule_reboot(100000);
+ break;
+
+ case PX4IO_P_SETUP_DSM:
+ dsm_bind(value & 0x0f, (value >> 4) & 0xF);
+ break;
+
default:
return -1;
}
@@ -361,9 +576,11 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
case PX4IO_PAGE_RC_CONFIG: {
- /* do not allow a RC config change while fully armed */
- if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
- /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
+ /**
+ * do not allow a RC config change while outputs armed
+ */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
break;
}
@@ -371,7 +588,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
unsigned index = offset - channel * PX4IO_P_RC_CONFIG_STRIDE;
uint16_t *conf = &r_page_rc_input_config[channel * PX4IO_P_RC_CONFIG_STRIDE];
- if (channel >= MAX_CONTROL_CHANNELS)
+ if (channel >= PX4IO_RC_INPUT_CHANNELS)
return -1;
/* disable the channel until we have a chance to sanity-check it */
@@ -391,6 +608,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
value &= PX4IO_P_RC_CONFIG_OPTIONS_VALID;
r_status_flags |= PX4IO_P_STATUS_FLAGS_INIT_OK;
+ /* clear any existing RC disabled flag */
+ r_setup_arming &= ~(PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED);
+
/* set all options except the enabled option */
conf[index] = value & ~PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
@@ -398,6 +618,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
/* this option is normally set last */
if (value & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
uint8_t count = 0;
+ bool disabled = false;
/* assert min..center..max ordering */
if (conf[PX4IO_P_RC_CONFIG_MIN] < 500) {
@@ -416,7 +637,10 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
if (conf[PX4IO_P_RC_CONFIG_DEADZONE] > 500) {
count++;
}
- if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= MAX_CONTROL_CHANNELS) {
+
+ if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] == UINT8_MAX) {
+ disabled = true;
+ } else if ((int)(conf[PX4IO_P_RC_CONFIG_ASSIGNMENT]) < 0 || conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
count++;
}
@@ -424,7 +648,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
if (count) {
isr_debug(0, "ERROR: %d config error(s) for RC%d.\n", count, (channel + 1));
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_INIT_OK;
- } else {
+ } else if (!disabled) {
conf[index] |= PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
}
}
@@ -436,6 +660,14 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
/* case PX4IO_RC_PAGE_CONFIG */
}
+ case PX4IO_PAGE_TEST:
+ switch (offset) {
+ case PX4IO_P_TEST_LED:
+ LED_AMBER(value & 1);
+ break;
+ }
+ break;
+
default:
return -1;
}
@@ -472,6 +704,7 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
/* PX4IO_P_STATUS_ALARMS maintained externally */
+#ifdef ADC_VBATT
/* PX4IO_P_STATUS_VBATT */
{
/*
@@ -505,7 +738,8 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
r_page_status[PX4IO_P_STATUS_VBATT] = corrected;
}
}
-
+#endif
+#ifdef ADC_IBATT
/* PX4IO_P_STATUS_IBATT */
{
/*
@@ -515,26 +749,60 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
FMU sort it out, with user selectable
configuration for their sensor
*/
- unsigned counts = adc_measure(ADC_IN5);
+ unsigned counts = adc_measure(ADC_IBATT);
if (counts != 0xffff) {
r_page_status[PX4IO_P_STATUS_IBATT] = counts;
}
}
+#endif
+#ifdef ADC_VSERVO
+ /* PX4IO_P_STATUS_VSERVO */
+ {
+ unsigned counts = adc_measure(ADC_VSERVO);
+ if (counts != 0xffff) {
+ // use 3:1 scaling on 3.3V ADC input
+ unsigned mV = counts * 9900 / 4096;
+ r_page_status[PX4IO_P_STATUS_VSERVO] = mV;
+ }
+ }
+#endif
+#ifdef ADC_RSSI
+ /* PX4IO_P_STATUS_VRSSI */
+ {
+ unsigned counts = adc_measure(ADC_RSSI);
+ if (counts != 0xffff) {
+ // use 1:1 scaling on 3.3V ADC input
+ unsigned mV = counts * 3300 / 4096;
+ r_page_status[PX4IO_P_STATUS_VRSSI] = mV;
+ }
+ }
+#endif
+ /* XXX PX4IO_P_STATUS_PRSSI */
SELECT_PAGE(r_page_status);
break;
case PX4IO_PAGE_RAW_ADC_INPUT:
memset(r_page_scratch, 0, sizeof(r_page_scratch));
+#ifdef ADC_VBATT
r_page_scratch[0] = adc_measure(ADC_VBATT);
- r_page_scratch[1] = adc_measure(ADC_IN5);
-
+#endif
+#ifdef ADC_IBATT
+ r_page_scratch[1] = adc_measure(ADC_IBATT);
+#endif
+
+#ifdef ADC_VSERVO
+ r_page_scratch[0] = adc_measure(ADC_VSERVO);
+#endif
+#ifdef ADC_RSSI
+ r_page_scratch[1] = adc_measure(ADC_RSSI);
+#endif
SELECT_PAGE(r_page_scratch);
break;
case PX4IO_PAGE_PWM_INFO:
memset(r_page_scratch, 0, sizeof(r_page_scratch));
- for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
+ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
r_page_scratch[PX4IO_RATE_MAP_BASE + i] = up_pwm_servo_get_rate_group(i);
SELECT_PAGE(r_page_scratch);
@@ -577,6 +845,15 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
case PX4IO_PAGE_FAILSAFE_PWM:
SELECT_PAGE(r_page_servo_failsafe);
break;
+ case PX4IO_PAGE_CONTROL_MIN_PWM:
+ SELECT_PAGE(r_page_servo_control_min);
+ break;
+ case PX4IO_PAGE_CONTROL_MAX_PWM:
+ SELECT_PAGE(r_page_servo_control_max);
+ break;
+ case PX4IO_PAGE_DISARMED_PWM:
+ SELECT_PAGE(r_page_servo_disarmed);
+ break;
default:
return -1;
@@ -606,7 +883,7 @@ static void
pwm_configure_rates(uint16_t map, uint16_t defaultrate, uint16_t altrate)
{
for (unsigned pass = 0; pass < 2; pass++) {
- for (unsigned group = 0; group < IO_SERVO_COUNT; group++) {
+ for (unsigned group = 0; group < PX4IO_SERVO_COUNT; group++) {
/* get the channel mask for this rate group */
uint32_t mask = up_pwm_servo_get_rate_group(group);
diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c
index 4dbecc274..ff2e4af6e 100644
--- a/src/modules/px4iofirmware/safety.c
+++ b/src/modules/px4iofirmware/safety.c
@@ -45,7 +45,6 @@
#include "px4io.h"
static struct hrt_call arming_call;
-static struct hrt_call heartbeat_call;
static struct hrt_call failsafe_call;
/*
@@ -77,7 +76,6 @@ static unsigned blink_counter = 0;
static bool safety_button_pressed;
static void safety_check_button(void *arg);
-static void heartbeat_blink(void *arg);
static void failsafe_blink(void *arg);
void
@@ -85,10 +83,11 @@ safety_init(void)
{
/* arrange for the button handler to be called at 10Hz */
hrt_call_every(&arming_call, 1000, 100000, safety_check_button, NULL);
+}
- /* arrange for the heartbeat handler to be called at 4Hz */
- hrt_call_every(&heartbeat_call, 1000, 250000, heartbeat_blink, NULL);
-
+void
+failsafe_led_init(void)
+{
/* arrange for the failsafe blinker to be called at 8Hz */
hrt_call_every(&failsafe_call, 1000, 125000, failsafe_blink, NULL);
}
@@ -110,7 +109,7 @@ safety_check_button(void *arg)
* state machine, keep ARM_COUNTER_THRESHOLD the same
* length in all cases of the if/else struct below.
*/
- if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
+ if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
(r_setup_arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK)) {
if (counter < ARM_COUNTER_THRESHOLD) {
@@ -118,18 +117,18 @@ safety_check_button(void *arg)
} else if (counter == ARM_COUNTER_THRESHOLD) {
/* switch to armed state */
- r_status_flags |= PX4IO_P_STATUS_FLAGS_ARMED;
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
counter++;
}
- } else if (safety_button_pressed && (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
+ } else if (safety_button_pressed && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
if (counter < ARM_COUNTER_THRESHOLD) {
counter++;
} else if (counter == ARM_COUNTER_THRESHOLD) {
/* change to disarmed state and notify the FMU */
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
counter++;
}
@@ -140,7 +139,7 @@ safety_check_button(void *arg)
/* Select the appropriate LED flash pattern depending on the current IO/FMU arm state */
uint16_t pattern = LED_PATTERN_FMU_REFUSE_TO_ARM;
- if (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) {
+ if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
if (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) {
pattern = LED_PATTERN_IO_FMU_ARMED;
@@ -164,23 +163,13 @@ safety_check_button(void *arg)
}
static void
-heartbeat_blink(void *arg)
-{
- static bool heartbeat = false;
-
- /* XXX add flags here that need to be frobbed by various loops */
-
- LED_BLUE(heartbeat = !heartbeat);
-}
-
-static void
failsafe_blink(void *arg)
{
/* indicate that a serious initialisation error occured */
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)) {
LED_AMBER(true);
- return;
- }
+ return;
+ }
static bool failsafe = false;
@@ -192,4 +181,4 @@ failsafe_blink(void *arg)
}
LED_AMBER(failsafe);
-} \ No newline at end of file
+}
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index 073ddeaba..f6ec542eb 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -54,6 +54,27 @@
#define SBUS_FRAME_SIZE 25
#define SBUS_INPUT_CHANNELS 16
+#define SBUS_FLAGS_BYTE 23
+#define SBUS_FAILSAFE_BIT 3
+#define SBUS_FRAMELOST_BIT 2
+
+/*
+ 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)
+ -+152% on TX: PCM 0.884/1.520/2.160ms -> SBus raw values: 1/1024/2047 (140% ATV plus dirty tricks)
+*/
+
+/* define range mapping here, -+100% -> 1000..2000 */
+#define SBUS_RANGE_MIN 200.0f
+#define SBUS_RANGE_MAX 1800.0f
+
+#define SBUS_TARGET_MIN 1000.0f
+#define SBUS_TARGET_MAX 2000.0f
+
+/* pre-calculate the floating point stuff as far as possible at compile time */
+#define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN))
+#define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f))
static int sbus_fd = -1;
@@ -66,7 +87,7 @@ static unsigned partial_frame_count;
unsigned sbus_frame_drops;
-static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values);
+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)
@@ -97,7 +118,7 @@ sbus_init(const char *device)
}
bool
-sbus_input(uint16_t *values, uint16_t *num_values)
+sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels)
{
ssize_t ret;
hrt_abstime now;
@@ -154,7 +175,7 @@ sbus_input(uint16_t *values, uint16_t *num_values)
* decode it.
*/
partial_frame_count = 0;
- return sbus_decode(now, values, num_values);
+ return sbus_decode(now, values, num_values, sbus_failsafe, sbus_frame_drop, max_channels);
}
/*
@@ -194,28 +215,41 @@ 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)
+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) || (frame[24] != 0x00)) {
+ if ((frame[0] != 0x0f)) {
sbus_frame_drops++;
return false;
}
- /* if the failsafe or connection lost bit is set, we consider the frame invalid */
- if ((frame[23] & (1 << 2)) && /* signal lost */
- (frame[23] & (1 << 3))) { /* failsafe */
-
- /* actively announce signal loss */
- *values = 0;
- return false;
+ switch (frame[24]) {
+ case 0x00:
+ /* this is S.BUS 1 */
+ break;
+ case 0x03:
+ /* S.BUS 2 SLOT0: RX battery and external voltage */
+ break;
+ case 0x83:
+ /* S.BUS 2 SLOT1 */
+ break;
+ case 0x43:
+ case 0xC3:
+ case 0x23:
+ case 0xA3:
+ case 0x63:
+ case 0xE3:
+ break;
+ default:
+ /* we expect one of the bits above, but there are some we don't know yet */
+ break;
}
/* we have received something we think is a frame */
last_frame_time = frame_time;
- unsigned chancount = (PX4IO_INPUT_CHANNELS > SBUS_INPUT_CHANNELS) ?
- SBUS_INPUT_CHANNELS : PX4IO_INPUT_CHANNELS;
+ unsigned chancount = (max_values > SBUS_INPUT_CHANNELS) ?
+ SBUS_INPUT_CHANNELS : max_values;
/* use the decoder matrix to extract channel data */
for (unsigned channel = 0; channel < chancount; channel++) {
@@ -234,22 +268,43 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
}
}
- /* convert 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
- values[channel] = (value / 2) + 998;
+
+ /* 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;
}
/* decode switch channels if data fields are wide enough */
- if (PX4IO_INPUT_CHANNELS > 17 && chancount > 15) {
+ if (PX4IO_RC_INPUT_CHANNELS > 17 && chancount > 15) {
chancount = 18;
/* channel 17 (index 16) */
- values[16] = (frame[23] & (1 << 0)) * 1000 + 998;
+ values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0)) * 1000 + 998;
/* channel 18 (index 17) */
- values[17] = (frame[23] & (1 << 1)) * 1000 + 998;
+ values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1)) * 1000 + 998;
}
/* note the number of channels decoded */
*num_values = chancount;
+ /* decode and handle failsafe and frame-lost flags */
+ if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
+ /* 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 */
+ /* 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,
+ * e.g. by prematurely issueing return-to-launch!!! */
+
+ *sbus_failsafe = false;
+ *sbus_frame_drop = true;
+ } else {
+ *sbus_failsafe = false;
+ *sbus_frame_drop = false;
+ }
+
return true;
}
diff --git a/src/modules/px4iofirmware/serial.c b/src/modules/px4iofirmware/serial.c
new file mode 100644
index 000000000..e9adc8cd6
--- /dev/null
+++ b/src/modules/px4iofirmware/serial.c
@@ -0,0 +1,338 @@
+/****************************************************************************
+ *
+ * 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 serial.c
+ *
+ * Serial communication for the PX4IO module.
+ */
+
+#include <stdint.h>
+#include <unistd.h>
+#include <termios.h>
+#include <fcntl.h>
+#include <string.h>
+
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+/* XXX might be able to prune these */
+#include <chip.h>
+#include <up_internal.h>
+#include <up_arch.h>
+#include <stm32.h>
+#include <systemlib/perf_counter.h>
+
+//#define DEBUG
+#include "px4io.h"
+
+static perf_counter_t pc_txns;
+static perf_counter_t pc_errors;
+static perf_counter_t pc_ore;
+static perf_counter_t pc_fe;
+static perf_counter_t pc_ne;
+static perf_counter_t pc_idle;
+static perf_counter_t pc_badidle;
+static perf_counter_t pc_regerr;
+static perf_counter_t pc_crcerr;
+
+static void rx_handle_packet(void);
+static void rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
+static DMA_HANDLE tx_dma;
+static DMA_HANDLE rx_dma;
+
+static int serial_interrupt(int irq, void *context);
+static void dma_reset(void);
+
+static struct IOPacket dma_packet;
+
+/* serial register accessors */
+#define REG(_x) (*(volatile uint32_t *)(PX4FMU_SERIAL_BASE + _x))
+#define rSR REG(STM32_USART_SR_OFFSET)
+#define rDR REG(STM32_USART_DR_OFFSET)
+#define rBRR REG(STM32_USART_BRR_OFFSET)
+#define rCR1 REG(STM32_USART_CR1_OFFSET)
+#define rCR2 REG(STM32_USART_CR2_OFFSET)
+#define rCR3 REG(STM32_USART_CR3_OFFSET)
+#define rGTPR REG(STM32_USART_GTPR_OFFSET)
+
+void
+interface_init(void)
+{
+ pc_txns = perf_alloc(PC_ELAPSED, "txns");
+ pc_errors = perf_alloc(PC_COUNT, "errors");
+ pc_ore = perf_alloc(PC_COUNT, "overrun");
+ pc_fe = perf_alloc(PC_COUNT, "framing");
+ pc_ne = perf_alloc(PC_COUNT, "noise");
+ pc_idle = perf_alloc(PC_COUNT, "idle");
+ pc_badidle = perf_alloc(PC_COUNT, "badidle");
+ pc_regerr = perf_alloc(PC_COUNT, "regerr");
+ pc_crcerr = perf_alloc(PC_COUNT, "crcerr");
+
+ /* allocate DMA */
+ tx_dma = stm32_dmachannel(PX4FMU_SERIAL_TX_DMA);
+ rx_dma = stm32_dmachannel(PX4FMU_SERIAL_RX_DMA);
+
+ /* configure pins for serial use */
+ stm32_configgpio(PX4FMU_SERIAL_TX_GPIO);
+ stm32_configgpio(PX4FMU_SERIAL_RX_GPIO);
+
+ /* reset and configure the UART */
+ rCR1 = 0;
+ rCR2 = 0;
+ rCR3 = 0;
+
+ /* clear status/errors */
+ (void)rSR;
+ (void)rDR;
+
+ /* configure line speed */
+ uint32_t usartdiv32 = PX4FMU_SERIAL_CLOCK / (PX4FMU_SERIAL_BITRATE / 2);
+ uint32_t mantissa = usartdiv32 >> 5;
+ uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
+
+ /* connect our interrupt */
+ irq_attach(PX4FMU_SERIAL_VECTOR, serial_interrupt);
+ up_enable_irq(PX4FMU_SERIAL_VECTOR);
+
+ /* enable UART and error/idle interrupts */
+ rCR3 = USART_CR3_EIE;
+ rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
+
+#if 0 /* keep this for signal integrity testing */
+ for (;;) {
+ while (!(rSR & USART_SR_TXE))
+ ;
+ rDR = 0xfa;
+ while (!(rSR & USART_SR_TXE))
+ ;
+ rDR = 0xa0;
+ }
+#endif
+
+ /* configure RX DMA and return to listening state */
+ dma_reset();
+
+ debug("serial init");
+}
+
+static void
+rx_handle_packet(void)
+{
+ /* check packet CRC */
+ uint8_t crc = dma_packet.crc;
+ dma_packet.crc = 0;
+ if (crc != crc_packet(&dma_packet)) {
+ perf_count(pc_crcerr);
+
+ /* send a CRC error reply */
+ dma_packet.count_code = PKT_CODE_CORRUPT;
+ dma_packet.page = 0xff;
+ dma_packet.offset = 0xff;
+
+ return;
+ }
+
+ if (PKT_CODE(dma_packet) == PKT_CODE_WRITE) {
+
+ /* it's a blind write - pass it on */
+ if (registers_set(dma_packet.page, dma_packet.offset, &dma_packet.regs[0], PKT_COUNT(dma_packet))) {
+ perf_count(pc_regerr);
+ dma_packet.count_code = PKT_CODE_ERROR;
+ } else {
+ dma_packet.count_code = PKT_CODE_SUCCESS;
+ }
+ return;
+ }
+
+ if (PKT_CODE(dma_packet) == PKT_CODE_READ) {
+
+ /* it's a read - get register pointer for reply */
+ unsigned count;
+ uint16_t *registers;
+
+ if (registers_get(dma_packet.page, dma_packet.offset, &registers, &count) < 0) {
+ perf_count(pc_regerr);
+ dma_packet.count_code = PKT_CODE_ERROR;
+ } else {
+ /* constrain reply to requested size */
+ if (count > PKT_MAX_REGS)
+ count = PKT_MAX_REGS;
+ if (count > PKT_COUNT(dma_packet))
+ count = PKT_COUNT(dma_packet);
+
+ /* copy reply registers into DMA buffer */
+ memcpy((void *)&dma_packet.regs[0], registers, count * 2);
+ dma_packet.count_code = count | PKT_CODE_SUCCESS;
+ }
+ return;
+ }
+
+ /* send a bad-packet error reply */
+ dma_packet.count_code = PKT_CODE_CORRUPT;
+ dma_packet.page = 0xff;
+ dma_packet.offset = 0xfe;
+}
+
+static void
+rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
+{
+ /*
+ * We are here because DMA completed, or UART reception stopped and
+ * we think we have a packet in the buffer.
+ */
+ perf_begin(pc_txns);
+
+ /* disable UART DMA */
+ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
+
+ /* handle the received packet */
+ rx_handle_packet();
+
+ /* re-set DMA for reception first, so we are ready to receive before we start sending */
+ dma_reset();
+
+ /* send the reply to the just-processed request */
+ dma_packet.crc = 0;
+ dma_packet.crc = crc_packet(&dma_packet);
+ stm32_dmasetup(
+ tx_dma,
+ (uint32_t)&rDR,
+ (uint32_t)&dma_packet,
+ PKT_SIZE(dma_packet),
+ DMA_CCR_DIR |
+ DMA_CCR_MINC |
+ DMA_CCR_PSIZE_8BITS |
+ DMA_CCR_MSIZE_8BITS);
+ stm32_dmastart(tx_dma, NULL, NULL, false);
+ rCR3 |= USART_CR3_DMAT;
+
+ perf_end(pc_txns);
+}
+
+static int
+serial_interrupt(int irq, void *context)
+{
+ static bool abort_on_idle = false;
+
+ uint32_t sr = rSR; /* get UART status register */
+ (void)rDR; /* required to clear any of the interrupt status that brought us here */
+
+ if (sr & (USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
+ USART_SR_NE | /* noise error - we have lost a byte due to noise */
+ USART_SR_FE)) { /* framing error - start/stop bit lost or line break */
+
+ perf_count(pc_errors);
+ if (sr & USART_SR_ORE)
+ perf_count(pc_ore);
+ if (sr & USART_SR_NE)
+ perf_count(pc_ne);
+ if (sr & USART_SR_FE)
+ perf_count(pc_fe);
+
+ /* send a line break - this will abort transmission/reception on the other end */
+ rCR1 |= USART_CR1_SBK;
+
+ /* when the line goes idle, abort rather than look at the packet */
+ abort_on_idle = true;
+ }
+
+ if (sr & USART_SR_IDLE) {
+
+ /*
+ * If we saw an error, don't bother looking at the packet - it should have
+ * been aborted by the sender and will definitely be bad. Get the DMA reconfigured
+ * ready for their retry.
+ */
+ if (abort_on_idle) {
+
+ abort_on_idle = false;
+ dma_reset();
+ return 0;
+ }
+
+ /*
+ * The sender has stopped sending - this is probably the end of a packet.
+ * Check the received length against the length in the header to see if
+ * we have something that looks like a packet.
+ */
+ unsigned length = sizeof(dma_packet) - stm32_dmaresidual(rx_dma);
+ if ((length < 1) || (length < PKT_SIZE(dma_packet))) {
+
+ /* it was too short - possibly truncated */
+ perf_count(pc_badidle);
+ dma_reset();
+ return 0;
+ }
+
+ /*
+ * Looks like we received a packet. Stop the DMA and go process the
+ * packet.
+ */
+ perf_count(pc_idle);
+ stm32_dmastop(rx_dma);
+ rx_dma_callback(rx_dma, DMA_STATUS_TCIF, NULL);
+ }
+
+ return 0;
+}
+
+static void
+dma_reset(void)
+{
+ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
+ (void)rSR;
+ (void)rDR;
+ (void)rDR;
+
+ /* kill any pending DMA */
+ stm32_dmastop(tx_dma);
+ stm32_dmastop(rx_dma);
+
+ /* reset the RX side */
+ stm32_dmasetup(
+ rx_dma,
+ (uint32_t)&rDR,
+ (uint32_t)&dma_packet,
+ sizeof(dma_packet),
+ DMA_CCR_MINC |
+ DMA_CCR_PSIZE_8BITS |
+ DMA_CCR_MSIZE_8BITS |
+ DMA_CCR_PRIVERYHI);
+
+ /* start receive DMA ready for the next packet */
+ stm32_dmastart(rx_dma, rx_dma_callback, NULL, false);
+ rCR3 |= USART_CR3_DMAR;
+}
+
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
new file mode 100644
index 000000000..6a29d7e5c
--- /dev/null
+++ b/src/modules/sdlog2/logbuffer.c
@@ -0,0 +1,133 @@
+/****************************************************************************
+ *
+ * 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 logbuffer.c
+ *
+ * Ring FIFO buffer for binary log data.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+
+#include "logbuffer.h"
+
+int logbuffer_init(struct logbuffer_s *lb, int size)
+{
+ lb->size = size;
+ lb->write_ptr = 0;
+ lb->read_ptr = 0;
+ lb->data = malloc(lb->size);
+ return (lb->data == 0) ? ERROR : OK;
+}
+
+int logbuffer_count(struct logbuffer_s *lb)
+{
+ int n = lb->write_ptr - lb->read_ptr;
+
+ if (n < 0) {
+ n += lb->size;
+ }
+
+ return n;
+}
+
+int logbuffer_is_empty(struct logbuffer_s *lb)
+{
+ return lb->read_ptr == lb->write_ptr;
+}
+
+bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size)
+{
+ // bytes available to write
+ int available = lb->read_ptr - lb->write_ptr - 1;
+
+ if (available < 0)
+ available += lb->size;
+
+ if (size > available) {
+ // buffer overflow
+ return false;
+ }
+
+ char *c = (char *) ptr;
+ int n = lb->size - lb->write_ptr; // bytes to end of the buffer
+
+ if (n < size) {
+ // message goes over end of the buffer
+ memcpy(&(lb->data[lb->write_ptr]), c, n);
+ lb->write_ptr = 0;
+
+ } else {
+ n = 0;
+ }
+
+ // now: n = bytes already written
+ int p = size - n; // number of bytes to write
+ memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p);
+ lb->write_ptr = (lb->write_ptr + p) % lb->size;
+ return true;
+}
+
+int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part)
+{
+ // bytes available to read
+ int available = lb->write_ptr - lb->read_ptr;
+
+ if (available == 0) {
+ return 0; // buffer is empty
+ }
+
+ int n = 0;
+
+ if (available > 0) {
+ // read pointer is before write pointer, all available bytes can be read
+ n = available;
+ *is_part = false;
+
+ } else {
+ // read pointer is after write pointer, read bytes from read_ptr to end of the buffer
+ n = lb->size - lb->read_ptr;
+ *is_part = lb->write_ptr > 0;
+ }
+
+ *ptr = &(lb->data[lb->read_ptr]);
+ return n;
+}
+
+void logbuffer_mark_read(struct logbuffer_s *lb, int n)
+{
+ lb->read_ptr = (lb->read_ptr + n) % lb->size;
+}
diff --git a/src/modules/mathlib/math/EulerAngles.hpp b/src/modules/sdlog2/logbuffer.h
index 399eecfa7..3a5e3a29f 100644
--- a/src/modules/mathlib/math/EulerAngles.hpp
+++ b/src/modules/sdlog2/logbuffer.h
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,43 +33,36 @@
****************************************************************************/
/**
- * @file Vector.h
+ * @file logbuffer.h
*
- * math vector
+ * Ring FIFO buffer for binary log data.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
-#pragma once
-
-#include "Vector.hpp"
+#ifndef SDLOG2_RINGBUFFER_H_
+#define SDLOG2_RINGBUFFER_H_
-namespace math
-{
+#include <stdbool.h>
-class Quaternion;
-class Dcm;
+struct logbuffer_s {
+ // pointers and size are in bytes
+ int write_ptr;
+ int read_ptr;
+ int size;
+ char *data;
+};
-class __EXPORT EulerAngles : public Vector
-{
-public:
- EulerAngles();
- EulerAngles(float phi, float theta, float psi);
- EulerAngles(const Quaternion &q);
- EulerAngles(const Dcm &dcm);
- virtual ~EulerAngles();
+int logbuffer_init(struct logbuffer_s *lb, int size);
- // alias
- void setPhi(float phi) { (*this)(0) = phi; }
- void setTheta(float theta) { (*this)(1) = theta; }
- void setPsi(float psi) { (*this)(2) = psi; }
+int logbuffer_count(struct logbuffer_s *lb);
- // const accessors
- const float &getPhi() const { return (*this)(0); }
- const float &getTheta() const { return (*this)(1); }
- const float &getPsi() const { return (*this)(2); }
+int logbuffer_is_empty(struct logbuffer_s *lb);
-};
+bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size);
-int __EXPORT eulerAnglesTest();
+int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part);
-} // math
+void logbuffer_mark_read(struct logbuffer_s *lb, int n);
+#endif
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
new file mode 100644
index 000000000..f53129688
--- /dev/null
+++ b/src/modules/sdlog2/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# sdlog2 Application
+#
+
+MODULE_COMMAND = sdlog2
+# The main thread only buffers to RAM, needs a high priority
+MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
+
+SRCS = sdlog2.c \
+ logbuffer.c
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
new file mode 100644
index 000000000..41e2248bb
--- /dev/null
+++ b/src/modules/sdlog2/sdlog2.c
@@ -0,0 +1,1463 @@
+/****************************************************************************
+ *
+ * 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 sdlog2.c
+ *
+ * Simple SD logger for flight data. Buffers new sensor values and
+ * does the heavy SD I/O in a low-priority worker thread.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <sys/prctl.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <poll.h>
+#include <stdlib.h>
+#include <string.h>
+#include <ctype.h>
+#include <systemlib/err.h>
+#include <unistd.h>
+#include <drivers/drv_hrt.h>
+#include <math.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vehicle_global_velocity_setpoint.h>
+#include <uORB/topics/optical_flow.h>
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/rc_channels.h>
+#include <uORB/topics/esc_status.h>
+
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <version/version.h>
+
+#include <mavlink/mavlink_log.h>
+
+#include "logbuffer.h"
+#include "sdlog2_format.h"
+#include "sdlog2_messages.h"
+
+#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
+ log_msgs_written++; \
+ } else { \
+ log_msgs_skipped++; \
+ }
+
+#define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \
+ fds[fdsc_count].fd = subs.##_var##_sub; \
+ fds[fdsc_count].events = POLLIN; \
+ fdsc_count++;
+
+static bool main_thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int deamon_task; /**< Handle of deamon task / thread */
+static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
+static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
+static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
+static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
+static const int MAX_WRITE_CHUNK = 512;
+static const int MIN_BYTES_TO_WRITE = 512;
+
+static const char *log_root = "/fs/microsd/log";
+static int mavlink_fd = -1;
+struct logbuffer_s lb;
+
+/* mutex / condition to synchronize threads */
+static pthread_mutex_t logbuffer_mutex;
+static pthread_cond_t logbuffer_cond;
+
+static char log_dir[32];
+
+/* statistics counters */
+static uint64_t start_time = 0;
+static unsigned long log_bytes_written = 0;
+static unsigned long log_msgs_written = 0;
+static unsigned long log_msgs_skipped = 0;
+
+/* GPS time, used for log files naming */
+static uint64_t gps_time = 0;
+
+/* current state of logging */
+static bool logging_enabled = false;
+/* enable logging on start (-e option) */
+static bool log_on_start = false;
+/* enable logging when armed (-a option) */
+static bool log_when_armed = false;
+/* delay = 1 / rate (rate defined by -r option) */
+static useconds_t sleep_delay = 0;
+/* use date/time for naming directories and files (-t option) */
+static bool log_name_timestamp = false;
+
+/* helper flag to track system state changes */
+static bool flag_system_armed = false;
+
+static pthread_t logwriter_pthread = 0;
+static pthread_attr_t logwriter_attr;
+
+/**
+ * Log buffer writing thread. Open and close file here.
+ */
+static void *logwriter_thread(void *arg);
+
+/**
+ * SD log management function.
+ */
+__EXPORT int sdlog2_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of sd log deamon.
+ */
+int sdlog2_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void sdlog2_usage(const char *reason);
+
+/**
+ * Print the current status.
+ */
+static void sdlog2_status(void);
+
+/**
+ * Start logging: create new file and start log writer thread.
+ */
+static void sdlog2_start_log(void);
+
+/**
+ * Stop logging: stop log writer thread and close log file.
+ */
+static void sdlog2_stop_log(void);
+
+/**
+ * Write a header to log file: list of message formats.
+ */
+static int write_formats(int fd);
+
+/**
+ * Write version message to log file.
+ */
+static int write_version(int fd);
+
+/**
+ * Write parameters to log file.
+ */
+static int write_parameters(int fd);
+
+static bool file_exist(const char *filename);
+
+static int file_copy(const char *file_old, const char *file_new);
+
+static void handle_command(struct vehicle_command_s *cmd);
+
+static void handle_status(struct vehicle_status_s *cmd);
+
+/**
+ * Create dir for current logging session. Store dir name in 'log_dir'.
+ */
+static int create_log_dir(void);
+
+/**
+ * Select first free log file name and open it.
+ */
+static int open_log_file(void);
+
+static void
+sdlog2_usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
+ "\t-r\tLog rate in Hz, 0 means unlimited rate\n"
+ "\t-b\tLog buffer size in KiB, default is 8\n"
+ "\t-e\tEnable logging by default (if not, can be started by command)\n"
+ "\t-a\tLog only when armed (can be still overriden by command)\n"
+ "\t-t\tUse date/time for naming log directories and files\n");
+}
+
+/**
+ * The logger deamon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_spawn().
+ */
+int sdlog2_main(int argc, char *argv[])
+{
+ if (argc < 2)
+ sdlog2_usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("already running");
+ /* this is not an error */
+ exit(0);
+ }
+
+ main_thread_should_exit = false;
+ deamon_task = task_spawn_cmd("sdlog2",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT - 30,
+ 3000,
+ sdlog2_thread_main,
+ (const char **)argv);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (!thread_running) {
+ warnx("not started");
+ }
+
+ main_thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ sdlog2_status();
+
+ } else {
+ warnx("not started\n");
+ }
+
+ exit(0);
+ }
+
+ sdlog2_usage("unrecognized command");
+ exit(1);
+}
+
+int create_log_dir()
+{
+ /* create dir on sdcard if needed */
+ uint16_t dir_number = 1; // start with dir sess001
+ int mkdir_ret;
+
+ if (log_name_timestamp && gps_time != 0) {
+ /* use GPS date for log dir naming: e.g. /fs/microsd/2014-01-19 */
+ time_t gps_time_sec = gps_time / 1000000;
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+ int n = snprintf(log_dir, sizeof(log_dir), "%s/", log_root);
+ strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &t);
+ mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
+
+ if (mkdir_ret == OK) {
+ warnx("log dir created: %s", log_dir);
+
+ } else if (errno != EEXIST) {
+ warn("failed creating new dir: %s", log_dir);
+ return -1;
+ }
+
+ } else {
+ /* look for the next dir that does not exist */
+ while (dir_number <= MAX_NO_LOGFOLDER) {
+ /* format log dir: e.g. /fs/microsd/sess001 */
+ sprintf(log_dir, "%s/sess%03u", log_root, dir_number);
+ mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
+
+ if (mkdir_ret == 0) {
+ warnx("log dir created: %s", log_dir);
+ break;
+
+ } else if (errno != EEXIST) {
+ warn("failed creating new dir: %s", log_dir);
+ return -1;
+ }
+
+ /* dir exists already */
+ dir_number++;
+ continue;
+ }
+
+ if (dir_number >= MAX_NO_LOGFOLDER) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
+ warnx("all %d possible dirs exist already", MAX_NO_LOGFOLDER);
+ return -1;
+ }
+ }
+
+ /* print logging path, important to find log file later */
+ warnx("log dir: %s", log_dir);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir);
+ return 0;
+}
+
+int open_log_file()
+{
+ /* string to hold the path to the log */
+ char log_file_name[16] = "";
+ char log_file_path[48] = "";
+
+ if (log_name_timestamp && gps_time != 0) {
+ /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t gps_time_sec = gps_time / 1000000;
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+ strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.bin", &t);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
+
+ } else {
+ uint16_t file_number = 1; // start with file log001
+
+ /* look for the next file that does not exist */
+ while (file_number <= MAX_NO_LOGFILE) {
+ /* format log file path: e.g. /fs/microsd/sess001/log001.bin */
+ snprintf(log_file_name, sizeof(log_file_name), "log%03u.bin", file_number);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
+
+ if (!file_exist(log_file_path)) {
+ break;
+ }
+
+ file_number++;
+ }
+
+ if (file_number > MAX_NO_LOGFILE) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
+ warnx("all %d possible files exist already", MAX_NO_LOGFILE);
+ return -1;
+ }
+ }
+
+ int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
+
+ if (fd < 0) {
+ warn("failed opening log: %s", log_file_name);
+ mavlink_log_info(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
+
+ } else {
+ warnx("log file: %s", log_file_name);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name);
+ }
+
+ return fd;
+}
+
+static void *logwriter_thread(void *arg)
+{
+ /* set name */
+ prctl(PR_SET_NAME, "sdlog2_writer", 0);
+
+ int log_fd = open_log_file();
+
+ if (log_fd < 0)
+ return;
+
+ struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
+
+ /* write log messages formats, version and parameters */
+ log_bytes_written += write_formats(log_fd);
+ log_bytes_written += write_version(log_fd);
+ log_bytes_written += write_parameters(log_fd);
+ fsync(log_fd);
+
+ int poll_count = 0;
+
+ void *read_ptr;
+ int n = 0;
+ bool should_wait = false;
+ bool is_part = false;
+
+ while (true) {
+ /* make sure threads are synchronized */
+ pthread_mutex_lock(&logbuffer_mutex);
+
+ /* update read pointer if needed */
+ if (n > 0) {
+ logbuffer_mark_read(&lb, n);
+ }
+
+ /* only wait if no data is available to process */
+ if (should_wait && !logwriter_should_exit) {
+ /* blocking wait for new data at this line */
+ pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex);
+ }
+
+ /* only get pointer to thread-safe data, do heavy I/O a few lines down */
+ int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part);
+
+ /* continue */
+ pthread_mutex_unlock(&logbuffer_mutex);
+
+ if (available > 0) {
+ /* do heavy IO here */
+ if (available > MAX_WRITE_CHUNK) {
+ n = MAX_WRITE_CHUNK;
+
+ } else {
+ n = available;
+ }
+
+ lseek(log_fd, 0, SEEK_CUR);
+ n = write(log_fd, read_ptr, n);
+
+ should_wait = (n == available) && !is_part;
+
+ if (n < 0) {
+ main_thread_should_exit = true;
+ err(1, "error writing log file");
+ }
+
+ if (n > 0) {
+ log_bytes_written += n;
+ }
+
+ } else {
+ n = 0;
+
+ /* exit only with empty buffer */
+ if (main_thread_should_exit || logwriter_should_exit) {
+ break;
+ }
+
+ should_wait = true;
+ }
+
+ if (++poll_count == 10) {
+ fsync(log_fd);
+ poll_count = 0;
+ }
+ }
+
+ fsync(log_fd);
+ close(log_fd);
+
+ return;
+}
+
+void sdlog2_start_log()
+{
+ warnx("start logging");
+ mavlink_log_info(mavlink_fd, "[sdlog2] start logging");
+
+ /* create log dir if needed */
+ if (create_log_dir() != 0) {
+ mavlink_log_critical(mavlink_fd, "[sdlog2] error creating log dir");
+ errx(1, "error creating log dir");
+ }
+
+ /* initialize statistics counter */
+ log_bytes_written = 0;
+ start_time = hrt_absolute_time();
+ log_msgs_written = 0;
+ log_msgs_skipped = 0;
+
+ /* initialize log buffer emptying thread */
+ pthread_attr_init(&logwriter_attr);
+
+ struct sched_param param;
+ /* low priority, as this is expensive disk I/O */
+ param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
+ (void)pthread_attr_setschedparam(&logwriter_attr, &param);
+
+ pthread_attr_setstacksize(&logwriter_attr, 2048);
+
+ logwriter_should_exit = false;
+
+ /* start log buffer emptying thread */
+ if (0 != pthread_create(&logwriter_pthread, &logwriter_attr, logwriter_thread, &lb)) {
+ errx(1, "error creating logwriter thread");
+ }
+
+ logging_enabled = true;
+}
+
+void sdlog2_stop_log()
+{
+ warnx("stop logging");
+ mavlink_log_info(mavlink_fd, "[sdlog2] stop logging");
+
+ logging_enabled = false;
+
+ /* wake up write thread one last time */
+ pthread_mutex_lock(&logbuffer_mutex);
+ logwriter_should_exit = true;
+ pthread_cond_signal(&logbuffer_cond);
+ /* unlock, now the writer thread may return */
+ pthread_mutex_unlock(&logbuffer_mutex);
+
+ /* wait for write thread to return */
+ int ret;
+
+ if ((ret = pthread_join(logwriter_pthread, NULL)) != 0) {
+ warnx("error joining logwriter thread: %i", ret);
+ }
+
+ logwriter_pthread = 0;
+ pthread_attr_destroy(&logwriter_attr);
+
+ sdlog2_status();
+}
+
+int write_formats(int fd)
+{
+ /* construct message format packet */
+ struct {
+ LOG_PACKET_HEADER;
+ struct log_format_s body;
+ } log_msg_format = {
+ LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG),
+ };
+
+ int written = 0;
+
+ /* fill message format packet for each format and write it */
+ for (int i = 0; i < log_formats_num; i++) {
+ log_msg_format.body = log_formats[i];
+ written += write(fd, &log_msg_format, sizeof(log_msg_format));
+ }
+
+ return written;
+}
+
+int write_version(int fd)
+{
+ /* construct version message */
+ struct {
+ LOG_PACKET_HEADER;
+ struct log_VER_s body;
+ } log_msg_VER = {
+ LOG_PACKET_HEADER_INIT(LOG_VER_MSG),
+ };
+
+ /* fill version message and write it */
+ strncpy(log_msg_VER.body.fw_git, FW_GIT, sizeof(log_msg_VER.body.fw_git));
+ strncpy(log_msg_VER.body.arch, HW_ARCH, sizeof(log_msg_VER.body.arch));
+ return write(fd, &log_msg_VER, sizeof(log_msg_VER));
+}
+
+int write_parameters(int fd)
+{
+ /* construct parameter message */
+ struct {
+ LOG_PACKET_HEADER;
+ struct log_PARM_s body;
+ } log_msg_PARM = {
+ LOG_PACKET_HEADER_INIT(LOG_PARM_MSG),
+ };
+
+ int written = 0;
+ param_t params_cnt = param_count();
+
+ for (param_t param = 0; param < params_cnt; param++) {
+ /* fill parameter message and write it */
+ strncpy(log_msg_PARM.body.name, param_name(param), sizeof(log_msg_PARM.body.name));
+ float value = NAN;
+
+ switch (param_type(param)) {
+ case PARAM_TYPE_INT32: {
+ int32_t i;
+ param_get(param, &i);
+ value = i; // cast integer to float
+ break;
+ }
+
+ case PARAM_TYPE_FLOAT:
+ param_get(param, &value);
+ break;
+
+ default:
+ break;
+ }
+
+ log_msg_PARM.body.value = value;
+ written += write(fd, &log_msg_PARM, sizeof(log_msg_PARM));
+ }
+
+ return written;
+}
+
+int sdlog2_thread_main(int argc, char *argv[])
+{
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ if (mavlink_fd < 0) {
+ warnx("failed to open MAVLink log stream, start mavlink app first");
+ }
+
+ /* log buffer size */
+ int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
+
+ logging_enabled = false;
+ log_on_start = false;
+ log_when_armed = false;
+ log_name_timestamp = false;
+
+ flag_system_armed = false;
+
+ /* work around some stupidity in task_create's argv handling */
+ argc -= 2;
+ argv += 2;
+ int ch;
+
+ while ((ch = getopt(argc, argv, "r:b:eat")) != EOF) {
+ switch (ch) {
+ case 'r': {
+ unsigned long r = strtoul(optarg, NULL, 10);
+
+ if (r == 0) {
+ sleep_delay = 0;
+
+ } else {
+ sleep_delay = 1000000 / r;
+ }
+ }
+ break;
+
+ case 'b': {
+ unsigned long s = strtoul(optarg, NULL, 10);
+
+ if (s < 1) {
+ s = 1;
+ }
+
+ log_buffer_size = 1024 * s;
+ }
+ break;
+
+ case 'e':
+ log_on_start = true;
+ break;
+
+ case 'a':
+ log_when_armed = true;
+ break;
+
+ case 't':
+ log_name_timestamp = true;
+ break;
+
+ case '?':
+ if (optopt == 'c') {
+ warnx("option -%c requires an argument", optopt);
+
+ } else if (isprint(optopt)) {
+ warnx("unknown option `-%c'", optopt);
+
+ } else {
+ warnx("unknown option character `\\x%x'", optopt);
+ }
+
+ default:
+ sdlog2_usage("unrecognized flag");
+ errx(1, "exiting");
+ }
+ }
+
+ gps_time = 0;
+
+ /* create log root dir */
+ int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
+
+ if (mkdir_ret != 0 && errno != EEXIST) {
+ err("failed creating log root dir: %s", log_root);
+ }
+
+ /* copy conversion scripts */
+ const char *converter_in = "/etc/logging/conv.zip";
+ char *converter_out = malloc(64);
+ snprintf(converter_out, 64, "%s/conv.zip", log_root);
+
+ if (file_copy(converter_in, converter_out) != OK) {
+ warn("unable to copy conversion scripts");
+ }
+
+ free(converter_out);
+
+ /* initialize log buffer with specified size */
+ warnx("log buffer size: %i bytes", log_buffer_size);
+
+ if (OK != logbuffer_init(&lb, log_buffer_size)) {
+ errx(1, "can't allocate log buffer, exiting");
+ }
+
+ struct vehicle_status_s buf_status;
+
+ memset(&buf_status, 0, sizeof(buf_status));
+
+ /* warning! using union here to save memory, elements should be used separately! */
+ union {
+ struct vehicle_command_s cmd;
+ struct sensor_combined_s sensor;
+ struct vehicle_attitude_s att;
+ struct vehicle_attitude_setpoint_s att_sp;
+ struct vehicle_rates_setpoint_s rates_sp;
+ struct actuator_outputs_s act_outputs;
+ struct actuator_controls_s act_controls;
+ struct vehicle_local_position_s local_pos;
+ struct vehicle_local_position_setpoint_s local_pos_sp;
+ struct vehicle_global_position_s global_pos;
+ struct vehicle_global_position_setpoint_s global_pos_sp;
+ struct vehicle_gps_position_s gps_pos;
+ struct vehicle_vicon_position_s vicon_pos;
+ struct optical_flow_s flow;
+ struct rc_channels_s rc;
+ struct differential_pressure_s diff_pres;
+ struct airspeed_s airspeed;
+ struct esc_status_s esc;
+ struct vehicle_global_velocity_setpoint_s global_vel_sp;
+ struct battery_status_s battery;
+ } buf;
+
+ memset(&buf, 0, sizeof(buf));
+
+ struct {
+ int cmd_sub;
+ int status_sub;
+ int sensor_sub;
+ int att_sub;
+ int att_sp_sub;
+ int rates_sp_sub;
+ int act_outputs_sub;
+ int act_controls_sub;
+ int local_pos_sub;
+ int local_pos_sp_sub;
+ int global_pos_sub;
+ int global_pos_sp_sub;
+ int gps_pos_sub;
+ int vicon_pos_sub;
+ int flow_sub;
+ int rc_sub;
+ int airspeed_sub;
+ int esc_sub;
+ int global_vel_sp_sub;
+ int battery_sub;
+ } subs;
+
+ /* log message buffer: header + body */
+#pragma pack(push, 1)
+ struct {
+ LOG_PACKET_HEADER;
+ union {
+ struct log_TIME_s log_TIME;
+ struct log_ATT_s log_ATT;
+ struct log_ATSP_s log_ATSP;
+ struct log_IMU_s log_IMU;
+ struct log_SENS_s log_SENS;
+ struct log_LPOS_s log_LPOS;
+ struct log_LPSP_s log_LPSP;
+ struct log_GPS_s log_GPS;
+ struct log_ATTC_s log_ATTC;
+ struct log_STAT_s log_STAT;
+ struct log_RC_s log_RC;
+ struct log_OUT0_s log_OUT0;
+ struct log_AIRS_s log_AIRS;
+ struct log_ARSP_s log_ARSP;
+ struct log_FLOW_s log_FLOW;
+ struct log_GPOS_s log_GPOS;
+ struct log_GPSP_s log_GPSP;
+ struct log_ESC_s log_ESC;
+ struct log_GVSP_s log_GVSP;
+ struct log_BATT_s log_BATT;
+ } body;
+ } log_msg = {
+ LOG_PACKET_HEADER_INIT(0)
+ };
+#pragma pack(pop)
+ memset(&log_msg.body, 0, sizeof(log_msg.body));
+
+ /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
+ /* number of messages */
+ const ssize_t fdsc = 25;
+ /* Sanity check variable and index */
+ ssize_t fdsc_count = 0;
+ /* file descriptors to wait for */
+ struct pollfd fds[fdsc];
+
+ /* --- VEHICLE COMMAND --- */
+ subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ fds[fdsc_count].fd = subs.cmd_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- VEHICLE STATUS --- */
+ subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ fds[fdsc_count].fd = subs.status_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- GPS POSITION --- */
+ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ fds[fdsc_count].fd = subs.gps_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- SENSORS COMBINED --- */
+ subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ fds[fdsc_count].fd = subs.sensor_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ATTITUDE --- */
+ subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ fds[fdsc_count].fd = subs.att_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ATTITUDE SETPOINT --- */
+ subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ fds[fdsc_count].fd = subs.att_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- RATES SETPOINT --- */
+ subs.rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
+ fds[fdsc_count].fd = subs.rates_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ACTUATOR OUTPUTS --- */
+ subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS);
+ fds[fdsc_count].fd = subs.act_outputs_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ACTUATOR CONTROL --- */
+ subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
+ fds[fdsc_count].fd = subs.act_controls_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- LOCAL POSITION --- */
+ subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
+ fds[fdsc_count].fd = subs.local_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- LOCAL POSITION SETPOINT --- */
+ subs.local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ fds[fdsc_count].fd = subs.local_pos_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- GLOBAL POSITION --- */
+ subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ fds[fdsc_count].fd = subs.global_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- GLOBAL POSITION SETPOINT--- */
+ subs.global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
+ fds[fdsc_count].fd = subs.global_pos_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- VICON POSITION --- */
+ subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
+ fds[fdsc_count].fd = subs.vicon_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- OPTICAL FLOW --- */
+ subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
+ fds[fdsc_count].fd = subs.flow_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- RC CHANNELS --- */
+ subs.rc_sub = orb_subscribe(ORB_ID(rc_channels));
+ fds[fdsc_count].fd = subs.rc_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- AIRSPEED --- */
+ subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ fds[fdsc_count].fd = subs.airspeed_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ESCs --- */
+ subs.esc_sub = orb_subscribe(ORB_ID(esc_status));
+ fds[fdsc_count].fd = subs.esc_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- GLOBAL VELOCITY SETPOINT --- */
+ subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
+ fds[fdsc_count].fd = subs.global_vel_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- BATTERY --- */
+ subs.battery_sub = orb_subscribe(ORB_ID(battery_status));
+ fds[fdsc_count].fd = subs.battery_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* WARNING: If you get the error message below,
+ * then the number of registered messages (fdsc)
+ * differs from the number of messages in the above list.
+ */
+ if (fdsc_count > fdsc) {
+ warn("WARNING: Not enough space for poll fds allocated. Check %s:%d", __FILE__, __LINE__);
+ fdsc_count = fdsc;
+ }
+
+ /*
+ * set up poll to block for new data,
+ * wait for a maximum of 1000 ms
+ */
+ const int poll_timeout = 1000;
+
+ thread_running = true;
+
+ /* initialize thread synchronization */
+ pthread_mutex_init(&logbuffer_mutex, NULL);
+ pthread_cond_init(&logbuffer_cond, NULL);
+
+ /* track changes in sensor_combined topic */
+ uint16_t gyro_counter = 0;
+ uint16_t accelerometer_counter = 0;
+ uint16_t magnetometer_counter = 0;
+ uint16_t baro_counter = 0;
+ uint16_t differential_pressure_counter = 0;
+
+ /* enable logging on start if needed */
+ if (log_on_start) {
+ /* check GPS topic to get GPS time */
+ if (log_name_timestamp) {
+ if (OK == orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos)) {
+ gps_time = buf.gps_pos.time_gps_usec;
+ }
+ }
+
+ sdlog2_start_log();
+ }
+
+ while (!main_thread_should_exit) {
+ /* decide use usleep() or blocking poll() */
+ bool use_sleep = sleep_delay > 0 && logging_enabled;
+
+ /* poll all topics if logging enabled or only management (first 2) if not */
+ int poll_ret = poll(fds, logging_enabled ? fdsc_count : 3, use_sleep ? 0 : poll_timeout);
+
+ /* handle the poll result */
+ if (poll_ret < 0) {
+ warnx("ERROR: poll error, stop logging");
+ main_thread_should_exit = true;
+
+ } else if (poll_ret > 0) {
+
+ /* check all data subscriptions only if logging enabled,
+ * logging_enabled can be changed while checking vehicle_command and vehicle_status */
+ bool check_data = logging_enabled;
+ int ifds = 0;
+ int handled_topics = 0;
+
+ /* --- VEHICLE COMMAND - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd);
+ handle_command(&buf.cmd);
+ handled_topics++;
+ }
+
+ /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
+
+ if (log_when_armed) {
+ handle_status(&buf_status);
+ }
+
+ handled_topics++;
+ }
+
+ /* --- GPS POSITION - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
+
+ if (log_name_timestamp) {
+ gps_time = buf.gps_pos.time_gps_usec;
+ }
+
+ handled_topics++;
+ }
+
+ if (!logging_enabled || !check_data || handled_topics >= poll_ret) {
+ continue;
+ }
+
+ ifds = 1; // begin from fds[1] again
+
+ pthread_mutex_lock(&logbuffer_mutex);
+
+ /* write time stamp message */
+ log_msg.msg_type = LOG_TIME_MSG;
+ log_msg.body.log_TIME.t = hrt_absolute_time();
+ LOGBUFFER_WRITE_AND_COUNT(TIME);
+
+ /* --- VEHICLE STATUS --- */
+ if (fds[ifds++].revents & POLLIN) {
+ // Don't orb_copy, it's already done few lines above
+ log_msg.msg_type = LOG_STAT_MSG;
+ log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
+ log_msg.body.log_STAT.navigation_state = (uint8_t) buf_status.navigation_state;
+ log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
+ log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
+ log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
+ log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
+ LOGBUFFER_WRITE_AND_COUNT(STAT);
+ }
+
+ /* --- GPS POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ // Don't orb_copy, it's already done few lines above
+ log_msg.msg_type = LOG_GPS_MSG;
+ log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec;
+ log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type;
+ log_msg.body.log_GPS.eph = buf.gps_pos.eph_m;
+ log_msg.body.log_GPS.epv = buf.gps_pos.epv_m;
+ log_msg.body.log_GPS.lat = buf.gps_pos.lat;
+ log_msg.body.log_GPS.lon = buf.gps_pos.lon;
+ log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001f;
+ log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s;
+ log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s;
+ log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s;
+ log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad;
+ LOGBUFFER_WRITE_AND_COUNT(GPS);
+ }
+
+ /* --- SENSOR COMBINED --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor);
+ bool write_IMU = false;
+ bool write_SENS = false;
+
+ if (buf.sensor.gyro_counter != gyro_counter) {
+ gyro_counter = buf.sensor.gyro_counter;
+ write_IMU = true;
+ }
+
+ if (buf.sensor.accelerometer_counter != accelerometer_counter) {
+ accelerometer_counter = buf.sensor.accelerometer_counter;
+ write_IMU = true;
+ }
+
+ if (buf.sensor.magnetometer_counter != magnetometer_counter) {
+ magnetometer_counter = buf.sensor.magnetometer_counter;
+ write_IMU = true;
+ }
+
+ if (buf.sensor.baro_counter != baro_counter) {
+ baro_counter = buf.sensor.baro_counter;
+ write_SENS = true;
+ }
+
+ if (buf.sensor.differential_pressure_counter != differential_pressure_counter) {
+ differential_pressure_counter = buf.sensor.differential_pressure_counter;
+ write_SENS = true;
+ }
+
+ if (write_IMU) {
+ log_msg.msg_type = LOG_IMU_MSG;
+ log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0];
+ log_msg.body.log_IMU.gyro_y = buf.sensor.gyro_rad_s[1];
+ log_msg.body.log_IMU.gyro_z = buf.sensor.gyro_rad_s[2];
+ log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer_m_s2[0];
+ log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer_m_s2[1];
+ log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer_m_s2[2];
+ log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0];
+ log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1];
+ log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2];
+ LOGBUFFER_WRITE_AND_COUNT(IMU);
+ }
+
+ if (write_SENS) {
+ log_msg.msg_type = LOG_SENS_MSG;
+ log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar;
+ log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter;
+ log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius;
+ log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa;
+ LOGBUFFER_WRITE_AND_COUNT(SENS);
+ }
+ }
+
+ /* --- ATTITUDE --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att);
+ log_msg.msg_type = LOG_ATT_MSG;
+ log_msg.body.log_ATT.roll = buf.att.roll;
+ log_msg.body.log_ATT.pitch = buf.att.pitch;
+ log_msg.body.log_ATT.yaw = buf.att.yaw;
+ log_msg.body.log_ATT.roll_rate = buf.att.rollspeed;
+ log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed;
+ log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed;
+ LOGBUFFER_WRITE_AND_COUNT(ATT);
+ }
+
+ /* --- ATTITUDE SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp);
+ log_msg.msg_type = LOG_ATSP_MSG;
+ log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body;
+ log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body;
+ log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body;
+ log_msg.body.log_ATSP.thrust_sp = buf.att_sp.thrust;
+ LOGBUFFER_WRITE_AND_COUNT(ATSP);
+ }
+
+ /* --- RATES SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_rates_setpoint), subs.rates_sp_sub, &buf.rates_sp);
+ log_msg.msg_type = LOG_ARSP_MSG;
+ log_msg.body.log_ARSP.roll_rate_sp = buf.rates_sp.roll;
+ log_msg.body.log_ARSP.pitch_rate_sp = buf.rates_sp.pitch;
+ log_msg.body.log_ARSP.yaw_rate_sp = buf.rates_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(ARSP);
+ }
+
+ /* --- ACTUATOR OUTPUTS --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs);
+ log_msg.msg_type = LOG_OUT0_MSG;
+ memcpy(log_msg.body.log_OUT0.output, buf.act_outputs.output, sizeof(log_msg.body.log_OUT0.output));
+ LOGBUFFER_WRITE_AND_COUNT(OUT0);
+ }
+
+ /* --- ACTUATOR CONTROL --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls);
+ log_msg.msg_type = LOG_ATTC_MSG;
+ log_msg.body.log_ATTC.roll = buf.act_controls.control[0];
+ log_msg.body.log_ATTC.pitch = buf.act_controls.control[1];
+ log_msg.body.log_ATTC.yaw = buf.act_controls.control[2];
+ log_msg.body.log_ATTC.thrust = buf.act_controls.control[3];
+ LOGBUFFER_WRITE_AND_COUNT(ATTC);
+ }
+
+ /* --- LOCAL POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos);
+ log_msg.msg_type = LOG_LPOS_MSG;
+ log_msg.body.log_LPOS.x = buf.local_pos.x;
+ log_msg.body.log_LPOS.y = buf.local_pos.y;
+ log_msg.body.log_LPOS.z = buf.local_pos.z;
+ log_msg.body.log_LPOS.vx = buf.local_pos.vx;
+ log_msg.body.log_LPOS.vy = buf.local_pos.vy;
+ log_msg.body.log_LPOS.vz = buf.local_pos.vz;
+ log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat;
+ log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon;
+ log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
+ log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
+ log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
+ log_msg.body.log_LPOS.landed = buf.local_pos.landed;
+ LOGBUFFER_WRITE_AND_COUNT(LPOS);
+ }
+
+ /* --- LOCAL POSITION SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp);
+ log_msg.msg_type = LOG_LPSP_MSG;
+ log_msg.body.log_LPSP.x = buf.local_pos_sp.x;
+ log_msg.body.log_LPSP.y = buf.local_pos_sp.y;
+ log_msg.body.log_LPSP.z = buf.local_pos_sp.z;
+ log_msg.body.log_LPSP.yaw = buf.local_pos_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(LPSP);
+ }
+
+ /* --- GLOBAL POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos);
+ log_msg.msg_type = LOG_GPOS_MSG;
+ log_msg.body.log_GPOS.lat = buf.global_pos.lat;
+ log_msg.body.log_GPOS.lon = buf.global_pos.lon;
+ log_msg.body.log_GPOS.alt = buf.global_pos.alt;
+ log_msg.body.log_GPOS.vel_n = buf.global_pos.vx;
+ log_msg.body.log_GPOS.vel_e = buf.global_pos.vy;
+ log_msg.body.log_GPOS.vel_d = buf.global_pos.vz;
+ LOGBUFFER_WRITE_AND_COUNT(GPOS);
+ }
+
+ /* --- GLOBAL POSITION SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_global_position_setpoint), subs.global_pos_sp_sub, &buf.global_pos_sp);
+ log_msg.msg_type = LOG_GPSP_MSG;
+ log_msg.body.log_GPSP.altitude_is_relative = buf.global_pos_sp.altitude_is_relative;
+ log_msg.body.log_GPSP.lat = buf.global_pos_sp.lat;
+ log_msg.body.log_GPSP.lon = buf.global_pos_sp.lon;
+ log_msg.body.log_GPSP.altitude = buf.global_pos_sp.altitude;
+ log_msg.body.log_GPSP.yaw = buf.global_pos_sp.yaw;
+ log_msg.body.log_GPSP.loiter_radius = buf.global_pos_sp.loiter_radius;
+ log_msg.body.log_GPSP.loiter_direction = buf.global_pos_sp.loiter_direction;
+ log_msg.body.log_GPSP.nav_cmd = buf.global_pos_sp.nav_cmd;
+ log_msg.body.log_GPSP.param1 = buf.global_pos_sp.param1;
+ log_msg.body.log_GPSP.param2 = buf.global_pos_sp.param2;
+ log_msg.body.log_GPSP.param3 = buf.global_pos_sp.param3;
+ log_msg.body.log_GPSP.param4 = buf.global_pos_sp.param4;
+ LOGBUFFER_WRITE_AND_COUNT(GPSP);
+ }
+
+ /* --- VICON POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos);
+ // TODO not implemented yet
+ }
+
+ /* --- FLOW --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow);
+ log_msg.msg_type = LOG_FLOW_MSG;
+ log_msg.body.log_FLOW.flow_raw_x = buf.flow.flow_raw_x;
+ log_msg.body.log_FLOW.flow_raw_y = buf.flow.flow_raw_y;
+ log_msg.body.log_FLOW.flow_comp_x = buf.flow.flow_comp_x_m;
+ log_msg.body.log_FLOW.flow_comp_y = buf.flow.flow_comp_y_m;
+ log_msg.body.log_FLOW.distance = buf.flow.ground_distance_m;
+ log_msg.body.log_FLOW.quality = buf.flow.quality;
+ log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
+ LOGBUFFER_WRITE_AND_COUNT(FLOW);
+ }
+
+ /* --- RC CHANNELS --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(rc_channels), subs.rc_sub, &buf.rc);
+ log_msg.msg_type = LOG_RC_MSG;
+ /* Copy only the first 8 channels of 14 */
+ memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel));
+ log_msg.body.log_RC.channel_count = buf.rc.chan_count;
+ LOGBUFFER_WRITE_AND_COUNT(RC);
+ }
+
+ /* --- AIRSPEED --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed);
+ log_msg.msg_type = LOG_AIRS_MSG;
+ log_msg.body.log_AIRS.indicated_airspeed = buf.airspeed.indicated_airspeed_m_s;
+ log_msg.body.log_AIRS.true_airspeed = buf.airspeed.true_airspeed_m_s;
+ LOGBUFFER_WRITE_AND_COUNT(AIRS);
+ }
+
+ /* --- ESCs --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(esc_status), subs.esc_sub, &buf.esc);
+
+ for (uint8_t i = 0; i < buf.esc.esc_count; i++) {
+ log_msg.msg_type = LOG_ESC_MSG;
+ log_msg.body.log_ESC.counter = buf.esc.counter;
+ log_msg.body.log_ESC.esc_count = buf.esc.esc_count;
+ log_msg.body.log_ESC.esc_connectiontype = buf.esc.esc_connectiontype;
+ log_msg.body.log_ESC.esc_num = i;
+ log_msg.body.log_ESC.esc_address = buf.esc.esc[i].esc_address;
+ log_msg.body.log_ESC.esc_version = buf.esc.esc[i].esc_version;
+ log_msg.body.log_ESC.esc_voltage = buf.esc.esc[i].esc_voltage;
+ log_msg.body.log_ESC.esc_current = buf.esc.esc[i].esc_current;
+ log_msg.body.log_ESC.esc_rpm = buf.esc.esc[i].esc_rpm;
+ log_msg.body.log_ESC.esc_temperature = buf.esc.esc[i].esc_temperature;
+ log_msg.body.log_ESC.esc_setpoint = buf.esc.esc[i].esc_setpoint;
+ log_msg.body.log_ESC.esc_setpoint_raw = buf.esc.esc[i].esc_setpoint_raw;
+ LOGBUFFER_WRITE_AND_COUNT(ESC);
+ }
+ }
+
+ /* --- GLOBAL VELOCITY SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_global_velocity_setpoint), subs.global_vel_sp_sub, &buf.global_vel_sp);
+ log_msg.msg_type = LOG_GVSP_MSG;
+ log_msg.body.log_GVSP.vx = buf.global_vel_sp.vx;
+ log_msg.body.log_GVSP.vy = buf.global_vel_sp.vy;
+ log_msg.body.log_GVSP.vz = buf.global_vel_sp.vz;
+ LOGBUFFER_WRITE_AND_COUNT(GVSP);
+ }
+
+ /* --- BATTERY --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(battery_status), subs.battery_sub, &buf.battery);
+ log_msg.msg_type = LOG_BATT_MSG;
+ log_msg.body.log_BATT.voltage = buf.battery.voltage_v;
+ log_msg.body.log_BATT.voltage_filtered = buf.battery.voltage_filtered_v;
+ log_msg.body.log_BATT.current = buf.battery.current_a;
+ log_msg.body.log_BATT.discharged = buf.battery.discharged_mah;
+ LOGBUFFER_WRITE_AND_COUNT(BATT);
+ }
+
+ /* 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 */
+ pthread_cond_signal(&logbuffer_cond);
+ }
+
+ /* unlock, now the writer thread may run */
+ pthread_mutex_unlock(&logbuffer_mutex);
+ }
+
+ if (use_sleep) {
+ usleep(sleep_delay);
+ }
+ }
+
+ if (logging_enabled)
+ sdlog2_stop_log();
+
+ pthread_mutex_destroy(&logbuffer_mutex);
+ pthread_cond_destroy(&logbuffer_cond);
+
+ free(lb.data);
+
+ warnx("exiting");
+
+ thread_running = false;
+
+ return 0;
+}
+
+void sdlog2_status()
+{
+ float kibibytes = log_bytes_written / 1024.0f;
+ float mebibytes = kibibytes / 1024.0f;
+ float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
+
+ warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
+ mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
+}
+
+/**
+ * @return 0 if file exists
+ */
+bool file_exist(const char *filename)
+{
+ struct stat buffer;
+ return stat(filename, &buffer) == 0;
+}
+
+int file_copy(const char *file_old, const char *file_new)
+{
+ FILE *source, *target;
+ source = fopen(file_old, "r");
+ int ret = 0;
+
+ if (source == NULL) {
+ warnx("failed opening input file to copy");
+ return 1;
+ }
+
+ target = fopen(file_new, "w");
+
+ if (target == NULL) {
+ fclose(source);
+ warnx("failed to open output file to copy");
+ return 1;
+ }
+
+ char buf[128];
+ int nread;
+
+ while ((nread = fread(buf, 1, sizeof(buf), source)) > 0) {
+ ret = fwrite(buf, 1, nread, target);
+
+ if (ret <= 0) {
+ warnx("error writing file");
+ ret = 1;
+ break;
+ }
+ }
+
+ fsync(fileno(target));
+
+ fclose(source);
+ fclose(target);
+
+ return OK;
+}
+
+void handle_command(struct vehicle_command_s *cmd)
+{
+ /* result of the command */
+ uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+ int param;
+
+ /* request to set different system mode */
+ switch (cmd->command) {
+
+ case VEHICLE_CMD_PREFLIGHT_STORAGE:
+ param = (int)(cmd->param3);
+
+ if (param == 1) {
+ sdlog2_start_log();
+
+ } else if (param == 0) {
+ sdlog2_stop_log();
+ }
+
+ break;
+
+ default:
+ /* silently ignore */
+ break;
+ }
+}
+
+void handle_status(struct vehicle_status_s *status)
+{
+ // TODO use flag from actuator_armed here?
+ bool armed = status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR;
+
+ if (armed != flag_system_armed) {
+ flag_system_armed = armed;
+
+ if (flag_system_armed) {
+ sdlog2_start_log();
+
+ } else {
+ sdlog2_stop_log();
+ }
+ }
+}
diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h
new file mode 100644
index 000000000..dc5e6c8bd
--- /dev/null
+++ b/src/modules/sdlog2/sdlog2_format.h
@@ -0,0 +1,98 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 sdlog2_format.h
+ *
+ * General log format structures and macro.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+/*
+Format characters in the format string for binary log messages
+ b : int8_t
+ B : uint8_t
+ h : int16_t
+ H : uint16_t
+ i : int32_t
+ I : uint32_t
+ f : float
+ n : char[4]
+ N : char[16]
+ Z : char[64]
+ c : int16_t * 100
+ C : uint16_t * 100
+ e : int32_t * 100
+ E : uint32_t * 100
+ L : int32_t latitude/longitude
+ M : uint8_t flight mode
+
+ q : int64_t
+ Q : uint64_t
+ */
+
+#ifndef SDLOG2_FORMAT_H_
+#define SDLOG2_FORMAT_H_
+
+#define LOG_PACKET_HEADER_LEN 3
+#define LOG_PACKET_HEADER uint8_t head1, head2, msg_type;
+#define LOG_PACKET_HEADER_INIT(id) .head1 = HEAD_BYTE1, .head2 = HEAD_BYTE2, .msg_type = id
+
+// once the logging code is all converted we will remove these from
+// this header
+#define HEAD_BYTE1 0xA3 // Decimal 163
+#define HEAD_BYTE2 0x95 // Decimal 149
+
+struct log_format_s {
+ uint8_t type;
+ uint8_t length; // full packet length including header
+ char name[4];
+ char format[16];
+ char labels[64];
+};
+
+#define LOG_FORMAT(_name, _format, _labels) { \
+ .type = LOG_##_name##_MSG, \
+ .length = sizeof(struct log_##_name##_s) + LOG_PACKET_HEADER_LEN, \
+ .name = #_name, \
+ .format = _format, \
+ .labels = _labels \
+ }
+
+#define LOG_FORMAT_MSG 0x80
+
+#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s)
+
+#endif /* SDLOG2_FORMAT_H_ */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
new file mode 100644
index 000000000..a784a1f30
--- /dev/null
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -0,0 +1,311 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 sdlog2_messages.h
+ *
+ * Log messages and structures definition.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef SDLOG2_MESSAGES_H_
+#define SDLOG2_MESSAGES_H_
+
+#include "sdlog2_format.h"
+
+/* define message formats */
+
+#pragma pack(push, 1)
+/* --- ATT - ATTITUDE --- */
+#define LOG_ATT_MSG 2
+struct log_ATT_s {
+ float roll;
+ float pitch;
+ float yaw;
+ float roll_rate;
+ float pitch_rate;
+ float yaw_rate;
+};
+
+/* --- ATSP - ATTITUDE SET POINT --- */
+#define LOG_ATSP_MSG 3
+struct log_ATSP_s {
+ float roll_sp;
+ float pitch_sp;
+ float yaw_sp;
+ float thrust_sp;
+};
+
+/* --- IMU - IMU SENSORS --- */
+#define LOG_IMU_MSG 4
+struct log_IMU_s {
+ float acc_x;
+ float acc_y;
+ float acc_z;
+ float gyro_x;
+ float gyro_y;
+ float gyro_z;
+ float mag_x;
+ float mag_y;
+ float mag_z;
+};
+
+/* --- SENS - OTHER SENSORS --- */
+#define LOG_SENS_MSG 5
+struct log_SENS_s {
+ float baro_pres;
+ float baro_alt;
+ float baro_temp;
+ float diff_pres;
+};
+
+/* --- LPOS - LOCAL POSITION --- */
+#define LOG_LPOS_MSG 6
+struct log_LPOS_s {
+ float x;
+ float y;
+ float z;
+ float vx;
+ float vy;
+ float vz;
+ int32_t ref_lat;
+ int32_t ref_lon;
+ float ref_alt;
+ uint8_t xy_flags;
+ uint8_t z_flags;
+ uint8_t landed;
+};
+
+/* --- LPSP - LOCAL POSITION SETPOINT --- */
+#define LOG_LPSP_MSG 7
+struct log_LPSP_s {
+ float x;
+ float y;
+ float z;
+ float yaw;
+};
+
+/* --- GPS - GPS POSITION --- */
+#define LOG_GPS_MSG 8
+struct log_GPS_s {
+ uint64_t gps_time;
+ uint8_t fix_type;
+ float eph;
+ float epv;
+ int32_t lat;
+ int32_t lon;
+ float alt;
+ float vel_n;
+ float vel_e;
+ float vel_d;
+ float cog;
+};
+
+/* --- ATTC - ATTITUDE CONTROLS (ACTUATOR_0 CONTROLS)--- */
+#define LOG_ATTC_MSG 9
+struct log_ATTC_s {
+ float roll;
+ float pitch;
+ float yaw;
+ float thrust;
+};
+
+/* --- STAT - VEHICLE STATE --- */
+#define LOG_STAT_MSG 10
+struct log_STAT_s {
+ uint8_t main_state;
+ uint8_t navigation_state;
+ uint8_t arming_state;
+ float battery_remaining;
+ uint8_t battery_warning;
+ uint8_t landed;
+};
+
+/* --- RC - RC INPUT CHANNELS --- */
+#define LOG_RC_MSG 11
+struct log_RC_s {
+ float channel[8];
+ uint8_t channel_count;
+};
+
+/* --- OUT0 - ACTUATOR_0 OUTPUT --- */
+#define LOG_OUT0_MSG 12
+struct log_OUT0_s {
+ float output[8];
+};
+
+/* --- AIRS - AIRSPEED --- */
+#define LOG_AIRS_MSG 13
+struct log_AIRS_s {
+ float indicated_airspeed;
+ float true_airspeed;
+};
+
+/* --- ARSP - ATTITUDE RATE SET POINT --- */
+#define LOG_ARSP_MSG 14
+struct log_ARSP_s {
+ float roll_rate_sp;
+ float pitch_rate_sp;
+ float yaw_rate_sp;
+};
+
+/* --- FLOW - OPTICAL FLOW --- */
+#define LOG_FLOW_MSG 15
+struct log_FLOW_s {
+ int16_t flow_raw_x;
+ int16_t flow_raw_y;
+ float flow_comp_x;
+ float flow_comp_y;
+ float distance;
+ uint8_t quality;
+ uint8_t sensor_id;
+};
+
+/* --- GPOS - GLOBAL POSITION ESTIMATE --- */
+#define LOG_GPOS_MSG 16
+struct log_GPOS_s {
+ int32_t lat;
+ int32_t lon;
+ float alt;
+ float vel_n;
+ float vel_e;
+ float vel_d;
+};
+
+/* --- GPSP - GLOBAL POSITION SETPOINT --- */
+#define LOG_GPSP_MSG 17
+struct log_GPSP_s {
+ uint8_t altitude_is_relative;
+ int32_t lat;
+ int32_t lon;
+ float altitude;
+ float yaw;
+ float loiter_radius;
+ int8_t loiter_direction;
+ uint8_t nav_cmd;
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+};
+
+/* --- ESC - ESC STATE --- */
+#define LOG_ESC_MSG 18
+struct log_ESC_s {
+ uint16_t counter;
+ 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_setpoint;
+ uint16_t esc_setpoint_raw;
+};
+
+/* --- GVSP - GLOBAL VELOCITY SETPOINT --- */
+#define LOG_GVSP_MSG 19
+struct log_GVSP_s {
+ float vx;
+ float vy;
+ float vz;
+};
+
+/* --- BATT - BATTERY --- */
+#define LOG_BATT_MSG 20
+struct log_BATT_s {
+ float voltage;
+ float voltage_filtered;
+ float current;
+ float discharged;
+};
+
+/* --- TIME - TIME STAMP --- */
+#define LOG_TIME_MSG 129
+struct log_TIME_s {
+ uint64_t t;
+};
+
+/* --- VER - VERSION --- */
+#define LOG_VER_MSG 130
+struct log_VER_s {
+ char arch[16];
+ char fw_git[64];
+};
+
+/* --- PARM - PARAMETER --- */
+#define LOG_PARM_MSG 131
+struct log_PARM_s {
+ char name[16];
+ float value;
+};
+
+#pragma pack(pop)
+
+/* construct list of all message formats */
+static const struct log_format_s log_formats[] = {
+ /* business-level messages, ID < 0x80 */
+ LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"),
+ LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
+ LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
+ LOG_FORMAT(LPOS, "ffffffLLfBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,XYFlags,ZFlags,Landed"),
+ LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
+ LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
+ LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
+ LOG_FORMAT(STAT, "BBBfBB", "MainState,NavState,ArmState,BatRem,BatWarn,Landed"),
+ LOG_FORMAT(RC, "ffffffffB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count"),
+ LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
+ LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
+ LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
+ LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
+ LOG_FORMAT(GPOS, "LLffff", "Lat,Lon,Alt,VelN,VelE,VelD"),
+ LOG_FORMAT(GPSP, "BLLfffbBffff", "AltRel,Lat,Lon,Alt,Yaw,LoiterR,LoiterDir,NavCmd,P1,P2,P3,P4"),
+ LOG_FORMAT(ESC, "HBBBHHHHHHfH", "Counter,NumESC,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"),
+ /* system-level messages, ID >= 0x80 */
+ // FMT: don't write format of format message, it's useless
+ LOG_FORMAT(TIME, "Q", "StartTime"),
+ LOG_FORMAT(VER, "NZ", "Arch,FwGit"),
+ LOG_FORMAT(PARM, "Nf", "Name,Value"),
+};
+
+static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);
+
+#endif /* SDLOG2_MESSAGES_H_ */
diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp
new file mode 100644
index 000000000..96a443c6e
--- /dev/null
+++ b/src/modules/segway/BlockSegwayController.cpp
@@ -0,0 +1,58 @@
+#include "BlockSegwayController.hpp"
+
+void BlockSegwayController::update() {
+ // wait for a sensor update, check for exit condition every 100 ms
+ if (poll(&_attPoll, 1, 100) < 0) return; // poll error
+
+ uint64_t newTimeStamp = hrt_absolute_time();
+ float dt = (newTimeStamp - _timeStamp) / 1.0e6f;
+ _timeStamp = newTimeStamp;
+
+ // check for sane values of dt
+ // to prevent large control responses
+ if (dt > 1.0f || dt < 0) return;
+
+ // set dt for all child blocks
+ setDt(dt);
+
+ // check for new updates
+ if (_param_update.updated()) updateParams();
+
+ // get new information from subscriptions
+ updateSubscriptions();
+
+ // default all output to zero unless handled by mode
+ for (unsigned i = 2; i < NUM_ACTUATOR_CONTROLS; i++)
+ _actuators.control[i] = 0.0f;
+
+ // only update guidance in auto mode
+ if (_status.main_state == MAIN_STATE_AUTO) {
+ // update guidance
+ }
+
+ // compute speed command
+ float spdCmd = -th2v.update(_att.pitch) - q2v.update(_att.pitchspeed);
+
+ // handle autopilot modes
+ if (_status.main_state == MAIN_STATE_AUTO ||
+ _status.main_state == MAIN_STATE_SEATBELT ||
+ _status.main_state == MAIN_STATE_EASY) {
+ _actuators.control[0] = spdCmd;
+ _actuators.control[1] = spdCmd;
+
+ } else if (_status.main_state == MAIN_STATE_MANUAL) {
+ if (_status.navigation_state == NAVIGATION_STATE_DIRECT) {
+ _actuators.control[CH_LEFT] = _manual.throttle;
+ _actuators.control[CH_RIGHT] = _manual.pitch;
+
+ } else if (_status.navigation_state == NAVIGATION_STATE_STABILIZE) {
+ _actuators.control[0] = spdCmd;
+ _actuators.control[1] = spdCmd;
+ }
+ }
+
+ // update all publications
+ updatePublications();
+
+}
+
diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp
new file mode 100644
index 000000000..4a01f785c
--- /dev/null
+++ b/src/modules/segway/BlockSegwayController.hpp
@@ -0,0 +1,27 @@
+#pragma once
+
+#include <controllib/uorb/blocks.hpp>
+
+using namespace control;
+
+class BlockSegwayController : public control::BlockUorbEnabledAutopilot {
+public:
+ BlockSegwayController() :
+ BlockUorbEnabledAutopilot(NULL,"SEG"),
+ th2v(this, "TH2V"),
+ q2v(this, "Q2V"),
+ _attPoll(),
+ _timeStamp(0)
+ {
+ _attPoll.fd = _att.getHandle();
+ _attPoll.events = POLLIN;
+ }
+ void update();
+private:
+ enum {CH_LEFT, CH_RIGHT};
+ BlockPI th2v;
+ BlockP q2v;
+ struct pollfd _attPoll;
+ uint64_t _timeStamp;
+};
+
diff --git a/src/modules/mathlib/module.mk b/src/modules/segway/module.mk
index bcdb2afe5..d5da85601 100644
--- a/src/modules/mathlib/module.mk
+++ b/src/modules/segway/module.mk
@@ -32,29 +32,11 @@
############################################################################
#
-# Math library
+# segway controller
#
-SRCS = math/test/test.cpp \
- math/Vector.cpp \
- math/Vector3.cpp \
- math/EulerAngles.cpp \
- math/Quaternion.cpp \
- math/Dcm.cpp \
- math/Matrix.cpp
-#
-# In order to include .config we first have to save off the
-# current makefile name, since app.mk needs it.
-#
-APP_MAKEFILE := $(lastword $(MAKEFILE_LIST))
--include $(TOPDIR)/.config
+MODULE_COMMAND = segway
-ifeq ($(CONFIG_ARCH_CORTEXM4)$(CONFIG_ARCH_FPU),yy)
-INCLUDE_DIRS += math/arm
-SRCS += math/arm/Vector.cpp \
- math/arm/Matrix.cpp
-else
-#INCLUDE_DIRS += math/generic
-#SRCS += math/generic/Vector.cpp \
-# math/generic/Matrix.cpp
-endif
+SRCS = segway_main.cpp \
+ BlockSegwayController.cpp \
+ params.c
diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c
new file mode 100644
index 000000000..d72923717
--- /dev/null
+++ b/src/modules/segway/params.c
@@ -0,0 +1,8 @@
+#include <systemlib/param/param.h>
+
+// 16 is max name length
+PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage
+PARAM_DEFINE_FLOAT(SEG_TH2V_I, 0.0f); // pitch integral to voltage
+PARAM_DEFINE_FLOAT(SEG_TH2V_I_MAX, 0.0f); // integral limiter
+PARAM_DEFINE_FLOAT(SEG_Q2V, 1.0f); // pitch rate to voltage
+
diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp
new file mode 100644
index 000000000..061fbf9b9
--- /dev/null
+++ b/src/modules/segway/segway_main.cpp
@@ -0,0 +1,157 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: James Goppert
+ *
+ * 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 segway_main.cpp
+ * @author James Goppert
+ *
+ * Segway controller using control library
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <math.h>
+
+#include "BlockSegwayController.hpp"
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int deamon_task; /**< Handle of deamon task / thread */
+
+/**
+ * Deamon management function.
+ */
+extern "C" __EXPORT int segway_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of deamon.
+ */
+int segway_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason);
+
+static void
+usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: segway {start|stop|status} [-p <additional params>]\n\n");
+ exit(1);
+}
+
+/**
+ * The deamon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int segway_main(int argc, char *argv[])
+{
+
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("already running");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+
+ deamon_task = task_spawn_cmd("segway",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 10,
+ 5120,
+ segway_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("is running");
+
+ } else {
+ warnx("not started");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+int segway_thread_main(int argc, char *argv[])
+{
+
+ warnx("starting");
+
+ using namespace control;
+
+ BlockSegwayController autopilot;
+
+ thread_running = true;
+
+ while (!thread_should_exit) {
+ autopilot.update();
+ }
+
+ warnx("exiting.");
+
+ thread_running = false;
+
+ return 0;
+}
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index ebbc580e1..aa538fd6b 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -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
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 230060148..30659fd3a 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.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
@@ -38,18 +35,109 @@
* @file sensor_params.c
*
* Parameters defined by the sensors task.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
+/**
+ * Gyro X offset
+ *
+ * This is an X-axis offset for the gyro. Adjust it according to the calibration data.
+ *
+ * @min -10.0
+ * @max 10.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
+
+/**
+ * Gyro Y offset
+ *
+ * @min -10.0
+ * @max 10.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
+
+/**
+ * Gyro Z offset
+ *
+ * @min -5.0
+ * @max 5.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
+/**
+ * Gyro X scaling
+ *
+ * X-axis scaling.
+ *
+ * @min -1.5
+ * @max 1.5
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
+
+/**
+ * Gyro Y scaling
+ *
+ * Y-axis scaling.
+ *
+ * @min -1.5
+ * @max 1.5
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
+
+/**
+ * Gyro Z scaling
+ *
+ * Z-axis scaling.
+ *
+ * @min -1.5
+ * @max 1.5
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
+
+/**
+ * Magnetometer X offset
+ *
+ * This is an X-axis offset for the magnetometer.
+ *
+ * @min -500.0
+ * @max 500.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
+
+/**
+ * Magnetometer Y offset
+ *
+ * This is an Y-axis offset for the magnetometer.
+ *
+ * @min -500.0
+ * @max 500.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
+
+/**
+ * Magnetometer Z offset
+ *
+ * This is an Z-axis offset for the magnetometer.
+ *
+ * @min -500.0
+ * @max 500.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
@@ -64,55 +152,157 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
-PARAM_DEFINE_INT32(SENS_DPRES_OFF, 1667);
+PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);
+PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
+PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
+PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
+
+/**
+ * RC Channel 1 Minimum
+ *
+ * Minimum value for RC channel 1
+ *
+ * @min 800.0
+ * @max 1500.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f);
+
+/**
+ * RC Channel 1 Trim
+ *
+ * Mid point value (same as min for throttle)
+ *
+ * @min 800.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
+
+/**
+ * RC Channel 1 Maximum
+ *
+ * Maximum value for RC channel 1
+ *
+ * @min 1500.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f);
+
+/**
+ * RC Channel 1 Reverse
+ *
+ * Set to -1 to reverse channel.
+ *
+ * @min -1.0
+ * @max 1.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC1_DZ, 0.0f);
-PARAM_DEFINE_FLOAT(RC2_MIN, 1000);
-PARAM_DEFINE_FLOAT(RC2_TRIM, 1500);
-PARAM_DEFINE_FLOAT(RC2_MAX, 2000);
+/**
+ * RC Channel 1 dead zone
+ *
+ * The +- range of this value around the trim value will be considered as zero.
+ *
+ * @min 0.0
+ * @max 100.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f);
+
+/**
+ * RC Channel 2 Minimum
+ *
+ * Minimum value for RC channel 2
+ *
+ * @min 800.0
+ * @max 1500.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_MIN, 1000.0f);
+
+/**
+ * RC Channel 2 Trim
+ *
+ * Mid point value (same as min for throttle)
+ *
+ * @min 800.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_TRIM, 1500.0f);
+
+/**
+ * RC Channel 2 Maximum
+ *
+ * Maximum value for RC channel 2
+ *
+ * @min 1500.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f);
+
+/**
+ * RC Channel 2 Reverse
+ *
+ * Set to -1 to reverse channel.
+ *
+ * @min -1.0
+ * @max 1.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC2_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC2_DZ, 0.0f);
+
+/**
+ * RC Channel 2 dead zone
+ *
+ * The +- range of this value around the trim value will be considered as zero.
+ *
+ * @min 0.0
+ * @max 100.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC3_MIN, 1000);
PARAM_DEFINE_FLOAT(RC3_TRIM, 1500);
PARAM_DEFINE_FLOAT(RC3_MAX, 2000);
PARAM_DEFINE_FLOAT(RC3_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC3_DZ, 0.0f);
+PARAM_DEFINE_FLOAT(RC3_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC4_MIN, 1000);
PARAM_DEFINE_FLOAT(RC4_TRIM, 1500);
PARAM_DEFINE_FLOAT(RC4_MAX, 2000);
PARAM_DEFINE_FLOAT(RC4_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC4_DZ, 30.0f);
+PARAM_DEFINE_FLOAT(RC4_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC5_MIN, 1000);
PARAM_DEFINE_FLOAT(RC5_TRIM, 1500);
PARAM_DEFINE_FLOAT(RC5_MAX, 2000);
PARAM_DEFINE_FLOAT(RC5_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC5_DZ, 0.0f);
+PARAM_DEFINE_FLOAT(RC5_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC6_MIN, 1000);
PARAM_DEFINE_FLOAT(RC6_TRIM, 1500);
PARAM_DEFINE_FLOAT(RC6_MAX, 2000);
PARAM_DEFINE_FLOAT(RC6_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC6_DZ, 0.0f);
+PARAM_DEFINE_FLOAT(RC6_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC7_MIN, 1000);
PARAM_DEFINE_FLOAT(RC7_TRIM, 1500);
PARAM_DEFINE_FLOAT(RC7_MAX, 2000);
PARAM_DEFINE_FLOAT(RC7_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC7_DZ, 0.0f);
+PARAM_DEFINE_FLOAT(RC7_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC8_MIN, 1000);
PARAM_DEFINE_FLOAT(RC8_TRIM, 1500);
PARAM_DEFINE_FLOAT(RC8_MAX, 2000);
PARAM_DEFINE_FLOAT(RC8_REV, 1.0f);
-PARAM_DEFINE_FLOAT(RC8_DZ, 0.0f);
+PARAM_DEFINE_FLOAT(RC8_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC9_MIN, 1000);
PARAM_DEFINE_FLOAT(RC9_TRIM, 1500);
@@ -150,32 +340,128 @@ PARAM_DEFINE_FLOAT(RC14_MAX, 2000);
PARAM_DEFINE_FLOAT(RC14_REV, 1.0f);
PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
-PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */
+PARAM_DEFINE_FLOAT(RC15_MIN, 1000);
+PARAM_DEFINE_FLOAT(RC15_TRIM, 1500);
+PARAM_DEFINE_FLOAT(RC15_MAX, 2000);
+PARAM_DEFINE_FLOAT(RC15_REV, 1.0f);
+PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f);
+
+PARAM_DEFINE_FLOAT(RC16_MIN, 1000);
+PARAM_DEFINE_FLOAT(RC16_TRIM, 1500);
+PARAM_DEFINE_FLOAT(RC16_MAX, 2000);
+PARAM_DEFINE_FLOAT(RC16_REV, 1.0f);
+PARAM_DEFINE_FLOAT(RC16_DZ, 0.0f);
+
+PARAM_DEFINE_FLOAT(RC17_MIN, 1000);
+PARAM_DEFINE_FLOAT(RC17_TRIM, 1500);
+PARAM_DEFINE_FLOAT(RC17_MAX, 2000);
+PARAM_DEFINE_FLOAT(RC17_REV, 1.0f);
+PARAM_DEFINE_FLOAT(RC17_DZ, 0.0f);
+
+PARAM_DEFINE_FLOAT(RC18_MIN, 1000);
+PARAM_DEFINE_FLOAT(RC18_TRIM, 1500);
+PARAM_DEFINE_FLOAT(RC18_MAX, 2000);
+PARAM_DEFINE_FLOAT(RC18_REV, 1.0f);
+PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f);
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
+#endif
+PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind */
+
+PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
+#else
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
-PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f));
+/* PX4IOAR: 0.00838095238 */
+/* FMU standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 */
+/* FMU with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) */
+PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.00459340659f);
+#endif
+PARAM_DEFINE_FLOAT(BAT_C_SCALING, 0.0124); /* scaling for 3DR power brick */
+/**
+ * Roll control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading roll inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_ROLL, 1);
+
+/**
+ * Pitch control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading pitch inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_PITCH, 2);
+
+/**
+ * Throttle control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading throttle inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 3);
+
+/**
+ * Yaw control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading yaw inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_YAW, 4);
-PARAM_DEFINE_INT32(RC_MAP_OVER_SW, 5);
-PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 6);
+/**
+ * Mode switch channel mapping.
+ *
+ * This is the main flight mode selector.
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for deciding about the main mode.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_SAS_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_RTL_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
-PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera yaw / azimuth */
-PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera pitch / tilt */
-PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera trigger */
-PARAM_DEFINE_INT32(RC_MAP_AUX4, 0); /**< default function: camera roll */
-PARAM_DEFINE_INT32(RC_MAP_AUX5, 0); /**< default function: payload drop */
+PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera pitch */
+PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
+PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera azimuth / yaw */
+
+PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.6f);
+PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.6f);
+PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 2.0f);
-PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.4f);
-PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.4f);
-PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 1.0f);
+PARAM_DEFINE_INT32(RC_FS_CH, 0); /**< RC failsafe channel, 0 = disable */
+PARAM_DEFINE_INT32(RC_FS_MODE, 0); /**< RC failsafe mode: 0 = too low means signal loss, 1 = too high means signal loss */
+PARAM_DEFINE_FLOAT(RC_FS_THR, 800); /**< RC failsafe PWM threshold */
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 8bf5fdbd0..b50a694eb 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -50,6 +50,7 @@
#include <stdio.h>
#include <errno.h>
#include <math.h>
+#include <mathlib/mathlib.h>
#include <nuttx/analog/adc.h>
@@ -60,20 +61,22 @@
#include <drivers/drv_baro.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_adc.h>
+#include <drivers/drv_airspeed.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
+#include <conversion/rotation.h>
-#include <systemlib/ppm_decode.h>
#include <systemlib/airspeed.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/differential_pressure.h>
@@ -91,13 +94,39 @@
#define BARO_HEALTH_COUNTER_LIMIT_OK 5
#define ADC_HEALTH_COUNTER_LIMIT_OK 5
+/**
+ * Analog layout:
+ * FMU:
+ * IN2 - battery voltage
+ * IN3 - battery current
+ * IN4 - 5V sense
+ * IN10 - spare (we could actually trim these from the set)
+ * IN11 - spare (we could actually trim these from the set)
+ * IN12 - spare (we could actually trim these from the set)
+ * IN13 - aux1
+ * IN14 - aux2
+ * IN15 - pressure sensor
+ *
+ * IO:
+ * IN4 - servo supply rail
+ * IN5 - analog RSSI
+ */
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
+#define ADC_BATTERY_CURRENT_CHANNEL -1
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
+#endif
-#define BAT_VOL_INITIAL 0.f
-#define BAT_VOL_LOWPASS_1 0.99f
-#define BAT_VOL_LOWPASS_2 0.01f
-#define VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS 3.5f
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+#define ADC_BATTERY_VOLTAGE_CHANNEL 2
+#define ADC_BATTERY_CURRENT_CHANNEL 3
+#define ADC_5V_RAIL_SENSE 4
+#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
+#endif
+
+#define BATT_V_LOWPASS 0.001f
+#define BATT_V_IGNORE_THRESHOLD 3.5f
/**
* HACK - true temperature is much less than indicated temperature in baro,
@@ -105,8 +134,6 @@
*/
#define PCB_TEMP_ESTIMATE_DEG 5.0f
-#define PPM_INPUT_TIMEOUT_INTERVAL 50000 /**< 50 ms timeout / 20 Hz */
-
#define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg)
/**
@@ -137,16 +164,14 @@ public:
int start();
private:
- static const unsigned _rc_max_chan_count = RC_CHANNELS_MAX; /**< maximum number of r/c channels we handle */
+ static const unsigned _rc_max_chan_count = RC_INPUT_MAX_CHANNELS; /**< maximum number of r/c channels we handle */
-#if CONFIG_HRT_PPM
- hrt_abstime _ppm_last_valid; /**< last time we got a valid ppm signal */
+ hrt_abstime _rc_last_valid; /**< last time we got a valid RC signal */
/**
- * Gather and publish PPM input data.
+ * Gather and publish RC input data.
*/
- void ppm_poll();
-#endif
+ void rc_poll();
/* XXX should not be here - should be own driver */
int _fd_adc; /**< ADC driver handle */
@@ -163,14 +188,15 @@ private:
int _mag_sub; /**< raw mag data subscription */
int _rc_sub; /**< raw rc channels data subscription */
int _baro_sub; /**< raw baro data subscription */
- int _airspeed_sub; /**< airspeed subscription */
- int _diff_pres_sub; /**< raw differential pressure subscription */
- int _vstatus_sub; /**< vehicle status subscription */
+ int _airspeed_sub; /**< airspeed subscription */
+ int _diff_pres_sub; /**< raw differential pressure subscription */
+ int _vcontrol_mode_sub; /**< vehicle control mode subscription */
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
orb_advert_t _sensor_pub; /**< combined sensor data topic */
orb_advert_t _manual_control_pub; /**< manual control signal topic */
+ orb_advert_t _actuator_group_3_pub; /**< manual control as actuator topic */
orb_advert_t _rc_pub; /**< raw r/c control topic */
orb_advert_t _battery_pub; /**< battery status */
orb_advert_t _airspeed_pub; /**< airspeed */
@@ -184,36 +210,44 @@ private:
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
+ math::Matrix _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
+ math::Matrix _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 */
+
struct {
float min[_rc_max_chan_count];
float trim[_rc_max_chan_count];
float max[_rc_max_chan_count];
float rev[_rc_max_chan_count];
float dz[_rc_max_chan_count];
- // float ex[_rc_max_chan_count];
float scaling_factor[_rc_max_chan_count];
float gyro_offset[3];
+ float gyro_scale[3];
float mag_offset[3];
float mag_scale[3];
float accel_offset[3];
float accel_scale[3];
- int diff_pres_offset_pa;
+ float diff_pres_offset_pa;
+ float diff_pres_analog_enabled;
- int rc_type;
+ int board_rotation;
+ int external_mag_rotation;
int rc_map_roll;
int rc_map_pitch;
int rc_map_yaw;
int rc_map_throttle;
- int rc_map_manual_override_sw;
- int rc_map_auto_mode_sw;
+ int rc_map_mode_sw;
+ int rc_map_return_sw;
+ int rc_map_assisted_sw;
+ int rc_map_mission_sw;
- int rc_map_manual_mode_sw;
- int rc_map_sas_mode_sw;
- int rc_map_rtl_sw;
- int rc_map_offboard_ctrl_mode_sw;
+// int rc_map_offboard_ctrl_mode_sw;
int rc_map_flaps;
@@ -228,7 +262,13 @@ private:
float rc_scale_yaw;
float rc_scale_flaps;
+ int rc_fs_ch;
+ int rc_fs_mode;
+ float rc_fs_thr;
+
float battery_voltage_scaling;
+ float battery_current_scaling;
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -237,30 +277,27 @@ private:
param_t max[_rc_max_chan_count];
param_t rev[_rc_max_chan_count];
param_t dz[_rc_max_chan_count];
- // param_t ex[_rc_max_chan_count];
- param_t rc_type;
-
- param_t rc_demix;
param_t gyro_offset[3];
+ param_t gyro_scale[3];
param_t accel_offset[3];
param_t accel_scale[3];
param_t mag_offset[3];
param_t mag_scale[3];
param_t diff_pres_offset_pa;
+ param_t diff_pres_analog_enabled;
param_t rc_map_roll;
param_t rc_map_pitch;
param_t rc_map_yaw;
param_t rc_map_throttle;
- param_t rc_map_manual_override_sw;
- param_t rc_map_auto_mode_sw;
+ param_t rc_map_mode_sw;
+ param_t rc_map_return_sw;
+ param_t rc_map_assisted_sw;
+ param_t rc_map_mission_sw;
- param_t rc_map_manual_mode_sw;
- param_t rc_map_sas_mode_sw;
- param_t rc_map_rtl_sw;
- param_t rc_map_offboard_ctrl_mode_sw;
+// param_t rc_map_offboard_ctrl_mode_sw;
param_t rc_map_flaps;
@@ -275,7 +312,16 @@ private:
param_t rc_scale_yaw;
param_t rc_scale_flaps;
+ param_t rc_fs_ch;
+ param_t rc_fs_mode;
+ param_t rc_fs_thr;
+
param_t battery_voltage_scaling;
+ param_t battery_current_scaling;
+
+ param_t board_rotation;
+ param_t external_mag_rotation;
+
} _parameter_handles; /**< handles for interesting parameters */
@@ -350,9 +396,9 @@ private:
void diff_pres_poll(struct sensor_combined_s &raw);
/**
- * Check for changes in vehicle status.
+ * Check for changes in vehicle control mode.
*/
- void vehicle_status_poll();
+ void vehicle_control_mode_poll();
/**
* Check for changes in parameters.
@@ -387,13 +433,11 @@ namespace sensors
#endif
static const int ERROR = -1;
-Sensors *g_sensors;
+Sensors *g_sensors = nullptr;
}
Sensors::Sensors() :
-#ifdef CONFIG_HRT_PPM
- _ppm_last_valid(0),
-#endif
+ _rc_last_valid(0),
_fd_adc(-1),
_last_adc(0),
@@ -409,20 +453,27 @@ Sensors::Sensors() :
_mag_sub(-1),
_rc_sub(-1),
_baro_sub(-1),
- _vstatus_sub(-1),
+ _vcontrol_mode_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
/* publications */
_sensor_pub(-1),
_manual_control_pub(-1),
+ _actuator_group_3_pub(-1),
_rc_pub(-1),
_battery_pub(-1),
_airspeed_pub(-1),
_diff_pres_pub(-1),
/* performance counters */
- _loop_perf(perf_alloc(PC_ELAPSED, "sensor task update"))
+ _loop_perf(perf_alloc(PC_ELAPSED, "sensor task update")),
+
+ _board_rotation(3, 3),
+ _external_mag_rotation(3, 3),
+ _mag_is_external(false),
+ _battery_discharged(0),
+ _battery_current_timestamp(0)
{
/* basic r/c parameters */
@@ -451,8 +502,6 @@ Sensors::Sensors() :
}
- _parameter_handles.rc_type = param_find("RC_TYPE");
-
/* mandatory input switched, mapped to channels 1-4 per default */
_parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL");
_parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
@@ -460,16 +509,16 @@ Sensors::Sensors() :
_parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
- _parameter_handles.rc_map_manual_override_sw = param_find("RC_MAP_OVER_SW");
- _parameter_handles.rc_map_auto_mode_sw = param_find("RC_MAP_MODE_SW");
+ _parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
+ _parameter_handles.rc_map_return_sw = param_find("RC_MAP_RETURN_SW");
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
- _parameter_handles.rc_map_manual_mode_sw = param_find("RC_MAP_MAN_SW");
- _parameter_handles.rc_map_sas_mode_sw = param_find("RC_MAP_SAS_SW");
- _parameter_handles.rc_map_rtl_sw = param_find("RC_MAP_RTL_SW");
- _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
+ _parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
+ _parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW");
+
+// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -482,10 +531,18 @@ Sensors::Sensors() :
_parameter_handles.rc_scale_yaw = param_find("RC_SCALE_YAW");
_parameter_handles.rc_scale_flaps = param_find("RC_SCALE_FLAPS");
+ /* RC failsafe */
+ _parameter_handles.rc_fs_ch = param_find("RC_FS_CH");
+ _parameter_handles.rc_fs_mode = param_find("RC_FS_MODE");
+ _parameter_handles.rc_fs_thr = param_find("RC_FS_THR");
+
/* gyro offsets */
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
_parameter_handles.gyro_offset[1] = param_find("SENS_GYRO_YOFF");
_parameter_handles.gyro_offset[2] = param_find("SENS_GYRO_ZOFF");
+ _parameter_handles.gyro_scale[0] = param_find("SENS_GYRO_XSCALE");
+ _parameter_handles.gyro_scale[1] = param_find("SENS_GYRO_YSCALE");
+ _parameter_handles.gyro_scale[2] = param_find("SENS_GYRO_ZSCALE");
/* accel offsets */
_parameter_handles.accel_offset[0] = param_find("SENS_ACC_XOFF");
@@ -506,8 +563,14 @@ Sensors::Sensors() :
/* Differential pressure offset */
_parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF");
+ _parameter_handles.diff_pres_analog_enabled = param_find("SENS_DPRES_ANA");
_parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING");
+ _parameter_handles.battery_current_scaling = param_find("BAT_C_SCALING");
+
+ /* rotations */
+ _parameter_handles.board_rotation = param_find("SENS_BOARD_ROT");
+ _parameter_handles.external_mag_rotation = param_find("SENS_EXT_MAG_ROT");
/* fetch initial parameter values */
parameters_update();
@@ -542,53 +605,39 @@ int
Sensors::parameters_update()
{
bool rc_valid = true;
+ float tmpScaleFactor = 0.0f;
+ float tmpRevFactor = 0.0f;
/* rc values */
- for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) {
+ for (unsigned int i = 0; i < _rc_max_chan_count; i++) {
- if (param_get(_parameter_handles.min[i], &(_parameters.min[i])) != OK) {
- warnx("Failed getting min for chan %d", i);
- }
-
- if (param_get(_parameter_handles.trim[i], &(_parameters.trim[i])) != OK) {
- warnx("Failed getting trim for chan %d", i);
- }
+ param_get(_parameter_handles.min[i], &(_parameters.min[i]));
+ param_get(_parameter_handles.trim[i], &(_parameters.trim[i]));
+ param_get(_parameter_handles.max[i], &(_parameters.max[i]));
+ param_get(_parameter_handles.rev[i], &(_parameters.rev[i]));
+ param_get(_parameter_handles.dz[i], &(_parameters.dz[i]));
- if (param_get(_parameter_handles.max[i], &(_parameters.max[i])) != OK) {
- warnx("Failed getting max for chan %d", i);
- }
-
- if (param_get(_parameter_handles.rev[i], &(_parameters.rev[i])) != OK) {
- warnx("Failed getting rev for chan %d", i);
- }
-
- if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) {
- warnx("Failed getting dead zone for chan %d", i);
- }
-
- _parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]);
+ tmpScaleFactor = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]);
+ tmpRevFactor = tmpScaleFactor * _parameters.rev[i];
/* handle blowup in the scaling factor calculation */
- if (!isfinite(_parameters.scaling_factor[i]) ||
- _parameters.scaling_factor[i] * _parameters.rev[i] < 0.000001f ||
- _parameters.scaling_factor[i] * _parameters.rev[i] > 0.2f) {
-
+ if (!isfinite(tmpScaleFactor) ||
+ (tmpRevFactor < 0.000001f) ||
+ (tmpRevFactor > 0.2f)) {
+ warnx("RC chan %u not sane, scaling: %8.6f, rev: %d", i, tmpScaleFactor, (int)(_parameters.rev[i]));
/* scaling factors do not make sense, lock them down */
- _parameters.scaling_factor[i] = 0;
+ _parameters.scaling_factor[i] = 0.0f;
rc_valid = false;
- }
+ } else {
+ _parameters.scaling_factor[i] = tmpScaleFactor;
+ }
}
/* handle wrong values */
if (!rc_valid)
warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
- /* remote control type */
- if (param_get(_parameter_handles.rc_type, &(_parameters.rc_type)) != OK) {
- warnx("Failed getting remote control type");
- }
-
/* channel mapping */
if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) {
warnx("Failed getting roll chan index");
@@ -606,69 +655,42 @@ Sensors::parameters_update()
warnx("Failed getting throttle chan index");
}
- if (param_get(_parameter_handles.rc_map_manual_override_sw, &(_parameters.rc_map_manual_override_sw)) != OK) {
- warnx("Failed getting override sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_auto_mode_sw, &(_parameters.rc_map_auto_mode_sw)) != OK) {
- warnx("Failed getting auto mode sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
- warnx("Failed getting flaps chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_manual_mode_sw, &(_parameters.rc_map_manual_mode_sw)) != OK) {
- warnx("Failed getting manual mode sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_rtl_sw, &(_parameters.rc_map_rtl_sw)) != OK) {
- warnx("Failed getting rtl sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_sas_mode_sw, &(_parameters.rc_map_sas_mode_sw)) != OK) {
- warnx("Failed getting sas mode sw chan index");
- }
-
- if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
- warnx("Failed getting offboard control mode sw chan index");
+ if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
+ warnx("Failed getting mode sw chan index");
}
- if (param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1)) != OK) {
- warnx("Failed getting mode aux 1 index");
+ if (param_get(_parameter_handles.rc_map_return_sw, &(_parameters.rc_map_return_sw)) != OK) {
+ warnx("Failed getting return sw chan index");
}
- if (param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2)) != OK) {
- warnx("Failed getting mode aux 2 index");
+ if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
+ warnx("Failed getting assisted sw chan index");
}
- if (param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3)) != OK) {
- warnx("Failed getting mode aux 3 index");
+ if (param_get(_parameter_handles.rc_map_mission_sw, &(_parameters.rc_map_mission_sw)) != OK) {
+ warnx("Failed getting mission sw chan index");
}
- if (param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4)) != OK) {
- warnx("Failed getting mode aux 4 index");
- }
-
- if (param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5)) != OK) {
- warnx("Failed getting mode aux 5 index");
- }
-
- if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) {
- warnx("Failed getting rc scaling for roll");
- }
-
- if (param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)) != OK) {
- warnx("Failed getting rc scaling for pitch");
- }
-
- if (param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)) != OK) {
- warnx("Failed getting rc scaling for yaw");
+ if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
+ warnx("Failed getting flaps chan index");
}
- if (param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)) != OK) {
- warnx("Failed getting rc scaling for flaps");
- }
+// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
+// warnx("Failed getting offboard control mode sw chan index");
+// }
+
+ param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1));
+ param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2));
+ param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
+ param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
+ param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
+ param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll));
+ param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch));
+ param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw));
+ param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps));
+ param_get(_parameter_handles.rc_fs_ch, &(_parameters.rc_fs_ch));
+ param_get(_parameter_handles.rc_fs_mode, &(_parameters.rc_fs_mode));
+ param_get(_parameter_handles.rc_fs_thr, &(_parameters.rc_fs_thr));
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -676,15 +698,14 @@ Sensors::parameters_update()
_rc.function[PITCH] = _parameters.rc_map_pitch - 1;
_rc.function[YAW] = _parameters.rc_map_yaw - 1;
- _rc.function[OVERRIDE] = _parameters.rc_map_manual_override_sw - 1;
- _rc.function[AUTO_MODE] = _parameters.rc_map_auto_mode_sw - 1;
+ _rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
+ _rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
+ _rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
+ _rc.function[MISSION] = _parameters.rc_map_mission_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
- _rc.function[MANUAL_MODE] = _parameters.rc_map_manual_mode_sw - 1;
- _rc.function[RTL] = _parameters.rc_map_rtl_sw - 1;
- _rc.function[SAS_MODE] = _parameters.rc_map_sas_mode_sw - 1;
- _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
+// _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
_rc.function[AUX_1] = _parameters.rc_map_aux1 - 1;
_rc.function[AUX_2] = _parameters.rc_map_aux2 - 1;
@@ -696,6 +717,9 @@ Sensors::parameters_update()
param_get(_parameter_handles.gyro_offset[0], &(_parameters.gyro_offset[0]));
param_get(_parameter_handles.gyro_offset[1], &(_parameters.gyro_offset[1]));
param_get(_parameter_handles.gyro_offset[2], &(_parameters.gyro_offset[2]));
+ param_get(_parameter_handles.gyro_scale[0], &(_parameters.gyro_scale[0]));
+ param_get(_parameter_handles.gyro_scale[1], &(_parameters.gyro_scale[1]));
+ param_get(_parameter_handles.gyro_scale[2], &(_parameters.gyro_scale[2]));
/* accel offsets */
param_get(_parameter_handles.accel_offset[0], &(_parameters.accel_offset[0]));
@@ -716,12 +740,24 @@ Sensors::parameters_update()
/* Airspeed offset */
param_get(_parameter_handles.diff_pres_offset_pa, &(_parameters.diff_pres_offset_pa));
+ param_get(_parameter_handles.diff_pres_analog_enabled, &(_parameters.diff_pres_analog_enabled));
/* scaling of ADC ticks to battery voltage */
if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) {
warnx("Failed updating voltage scaling param");
}
+ /* scaling of ADC ticks to battery current */
+ if (param_get(_parameter_handles.battery_current_scaling, &(_parameters.battery_current_scaling)) != OK) {
+ warnx("Failed updating current scaling param");
+ }
+
+ param_get(_parameter_handles.board_rotation, &(_parameters.board_rotation));
+ param_get(_parameter_handles.external_mag_rotation, &(_parameters.external_mag_rotation));
+
+ get_rot_matrix((enum Rotation)_parameters.board_rotation, &_board_rotation);
+ get_rot_matrix((enum Rotation)_parameters.external_mag_rotation, &_external_mag_rotation);
+
return OK;
}
@@ -737,13 +773,30 @@ Sensors::accel_init()
errx(1, "FATAL: no accelerometer found");
} else {
- /* set the accel internal sampling rate up to at leat 500Hz */
- ioctl(fd, ACCELIOCSSAMPLERATE, 500);
- /* set the driver to poll at 500Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, 500);
+ // XXX do the check more elegantly
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* set the accel internal sampling rate up to at leat 1000Hz */
+ ioctl(fd, ACCELIOCSSAMPLERATE, 1000);
+
+ /* set the driver to poll at 1000Hz */
+ ioctl(fd, SENSORIOCSPOLLRATE, 1000);
+
+#elif CONFIG_ARCH_BOARD_PX4FMU_V2
+
+ /* set the accel internal sampling rate up to at leat 800Hz */
+ ioctl(fd, ACCELIOCSSAMPLERATE, 800);
+
+ /* set the driver to poll at 800Hz */
+ ioctl(fd, SENSORIOCSPOLLRATE, 800);
+
+#else
+#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+
+#endif
- warnx("using system accel");
close(fd);
}
}
@@ -760,13 +813,29 @@ Sensors::gyro_init()
errx(1, "FATAL: no gyro found");
} else {
- /* set the gyro internal sampling rate up to at leat 500Hz */
- ioctl(fd, GYROIOCSSAMPLERATE, 500);
- /* set the driver to poll at 500Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, 500);
+ // XXX do the check more elegantly
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* set the gyro internal sampling rate up to at least 1000Hz */
+ if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
+ ioctl(fd, GYROIOCSSAMPLERATE, 800);
+
+ /* set the driver to poll at 1000Hz */
+ if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
+ ioctl(fd, SENSORIOCSPOLLRATE, 800);
+
+#else
+
+ /* set the gyro internal sampling rate up to at least 760Hz */
+ ioctl(fd, GYROIOCSSAMPLERATE, 760);
+
+ /* set the driver to poll at 760Hz */
+ ioctl(fd, SENSORIOCSPOLLRATE, 760);
+
+#endif
- warnx("using system gyro");
close(fd);
}
}
@@ -775,6 +844,7 @@ void
Sensors::mag_init()
{
int fd;
+ int ret;
fd = open(MAG_DEVICE_PATH, 0);
@@ -783,11 +853,38 @@ Sensors::mag_init()
errx(1, "FATAL: no magnetometer found");
}
- /* set the mag internal poll rate to at least 150Hz */
- ioctl(fd, MAGIOCSSAMPLERATE, 150);
+ /* try different mag sampling rates */
- /* set the driver to poll at 150Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, 150);
+
+ ret = ioctl(fd, MAGIOCSSAMPLERATE, 150);
+
+ if (ret == OK) {
+ /* set the pollrate accordingly */
+ ioctl(fd, SENSORIOCSPOLLRATE, 150);
+
+ } else {
+ ret = ioctl(fd, MAGIOCSSAMPLERATE, 100);
+
+ /* if the slower sampling rate still fails, something is wrong */
+ if (ret == OK) {
+ /* set the driver to poll also at the slower rate */
+ ioctl(fd, SENSORIOCSPOLLRATE, 100);
+
+ } else {
+ errx(1, "FATAL: mag sampling rate could not be set");
+ }
+ }
+
+
+
+ ret = ioctl(fd, MAGIOCGEXTERNAL, 0);
+
+ if (ret < 0)
+ errx(1, "FATAL: unknown if magnetometer is external or onboard");
+ else if (ret == 1)
+ _mag_is_external = true;
+ else
+ _mag_is_external = false;
close(fd);
}
@@ -801,7 +898,7 @@ Sensors::baro_init()
if (fd < 0) {
warn("%s", BARO_DEVICE_PATH);
- warnx("No barometer found, ignoring");
+ errx(1, "FATAL: No barometer found");
}
/* set the driver to poll at 150Hz */
@@ -833,9 +930,12 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
- raw.accelerometer_m_s2[0] = accel_report.x;
- raw.accelerometer_m_s2[1] = accel_report.y;
- raw.accelerometer_m_s2[2] = accel_report.z;
+ math::Vector3 vect = {accel_report.x, accel_report.y, accel_report.z};
+ vect = _board_rotation * vect;
+
+ raw.accelerometer_m_s2[0] = vect(0);
+ raw.accelerometer_m_s2[1] = vect(1);
+ raw.accelerometer_m_s2[2] = vect(2);
raw.accelerometer_raw[0] = accel_report.x_raw;
raw.accelerometer_raw[1] = accel_report.y_raw;
@@ -856,9 +956,12 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);
- raw.gyro_rad_s[0] = gyro_report.x;
- raw.gyro_rad_s[1] = gyro_report.y;
- raw.gyro_rad_s[2] = gyro_report.z;
+ math::Vector3 vect = {gyro_report.x, gyro_report.y, gyro_report.z};
+ vect = _board_rotation * vect;
+
+ raw.gyro_rad_s[0] = vect(0);
+ raw.gyro_rad_s[1] = vect(1);
+ raw.gyro_rad_s[2] = vect(2);
raw.gyro_raw[0] = gyro_report.x_raw;
raw.gyro_raw[1] = gyro_report.y_raw;
@@ -879,9 +982,16 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_mag), _mag_sub, &mag_report);
- raw.magnetometer_ga[0] = mag_report.x;
- raw.magnetometer_ga[1] = mag_report.y;
- raw.magnetometer_ga[2] = mag_report.z;
+ math::Vector3 vect = {mag_report.x, mag_report.y, mag_report.z};
+
+ if (_mag_is_external)
+ vect = _external_mag_rotation * vect;
+ else
+ vect = _board_rotation * vect;
+
+ raw.magnetometer_ga[0] = vect(0);
+ raw.magnetometer_ga[1] = vect(1);
+ raw.magnetometer_ga[2] = vect(2);
raw.magnetometer_raw[0] = mag_report.x_raw;
raw.magnetometer_raw[1] = mag_report.y_raw;
@@ -922,8 +1032,8 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
raw.differential_pressure_counter++;
_airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_pa);
- _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f,
- raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
+ _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar * 1e2f,
+ raw.baro_pres_mbar * 1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
/* announce the airspeed if needed, just publish else */
if (_airspeed_pub > 0) {
@@ -936,21 +1046,21 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
}
void
-Sensors::vehicle_status_poll()
+Sensors::vehicle_control_mode_poll()
{
- struct vehicle_status_s vstatus;
- bool vstatus_updated;
+ struct vehicle_control_mode_s vcontrol_mode;
+ bool vcontrol_mode_updated;
- /* Check HIL state if vehicle status has changed */
- orb_check(_vstatus_sub, &vstatus_updated);
+ /* Check HIL state if vehicle control mode has changed */
+ orb_check(_vcontrol_mode_sub, &vcontrol_mode_updated);
- if (vstatus_updated) {
+ if (vcontrol_mode_updated) {
- orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &vstatus);
+ orb_copy(ORB_ID(vehicle_control_mode), _vcontrol_mode_sub, &vcontrol_mode);
/* switching from non-HIL to HIL mode */
//printf("[sensors] Vehicle mode: %i \t AND: %i, HIL: %i\n", vstatus.mode, vstatus.mode & VEHICLE_MODE_FLAG_HIL_ENABLED, hil_enabled);
- if (vstatus.flag_hil_enabled && !_hil_enabled) {
+ if (vcontrol_mode.flag_system_hil_enabled && !_hil_enabled) {
_hil_enabled = true;
_publishing = false;
@@ -983,11 +1093,11 @@ Sensors::parameter_update_poll(bool forced)
int fd = open(GYRO_DEVICE_PATH, 0);
struct gyro_scale gscale = {
_parameters.gyro_offset[0],
- 1.0f,
+ _parameters.gyro_scale[0],
_parameters.gyro_offset[1],
- 1.0f,
+ _parameters.gyro_scale[1],
_parameters.gyro_offset[2],
- 1.0f,
+ _parameters.gyro_scale[2],
};
if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
@@ -1025,6 +1135,21 @@ Sensors::parameter_update_poll(bool forced)
close(fd);
+ fd = open(AIRSPEED_DEVICE_PATH, 0);
+
+ /* this sensor is optional, abort without error */
+
+ if (fd > 0) {
+ struct airspeed_scale airscale = {
+ _parameters.diff_pres_offset_pa,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale))
+ warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ close(fd);
+ }
+
#if 0
printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]);
printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]);
@@ -1038,21 +1163,23 @@ Sensors::parameter_update_poll(bool forced)
void
Sensors::adc_poll(struct sensor_combined_s &raw)
{
+ /* only read if publishing */
+ if (!_publishing)
+ return;
+ hrt_abstime t = hrt_absolute_time();
/* rate limit to 100 Hz */
- if (hrt_absolute_time() - _last_adc >= 10000) {
+ if (t - _last_adc >= 10000) {
/* make space for a maximum of eight channels */
struct adc_msg_s buf_adc[8];
/* read all channels available */
int ret = read(_fd_adc, &buf_adc, sizeof(buf_adc));
- for (unsigned i = 0; i < sizeof(buf_adc) / sizeof(buf_adc[0]); i++) {
-
- if (ret >= (int)sizeof(buf_adc[0])) {
-
+ if (ret >= (int)sizeof(buf_adc[0])) {
+ for (unsigned i = 0; i < sizeof(buf_adc) / sizeof(buf_adc[0]); i++) {
/* Save raw voltage values */
if (i < (sizeof(raw.adc_voltage_v)) / sizeof(raw.adc_voltage_v[0])) {
- raw.adc_voltage_v[i] = buf_adc[i].am_data / (4096.0f / 3.3f);
+ raw.adc_voltage_v[i] = buf_adc[i].am_data / (4096.0f / 3.3f);
}
/* look for specific channels and process the raw voltage to measurement data */
@@ -1060,42 +1187,56 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
/* Voltage in volts */
float voltage = (buf_adc[i].am_data * _parameters.battery_voltage_scaling);
- if (voltage > VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS) {
-
+ if (voltage > BATT_V_IGNORE_THRESHOLD) {
+ _battery_status.voltage_v = voltage;
/* one-time initialization of low-pass value to avoid long init delays */
- if (_battery_status.voltage_v < 3.0f) {
- _battery_status.voltage_v = voltage;
+ if (_battery_status.voltage_filtered_v < BATT_V_IGNORE_THRESHOLD) {
+ _battery_status.voltage_filtered_v = voltage;
}
- _battery_status.timestamp = hrt_absolute_time();
- _battery_status.voltage_v = (BAT_VOL_LOWPASS_1 * (_battery_status.voltage_v + BAT_VOL_LOWPASS_2 * voltage));;
- /* current and discharge are unknown */
- _battery_status.current_a = -1.0f;
- _battery_status.discharged_mah = -1.0f;
+ _battery_status.timestamp = t;
+ _battery_status.voltage_filtered_v += (voltage - _battery_status.voltage_filtered_v) * BATT_V_LOWPASS;
- /* announce the battery voltage if needed, just publish else */
- if (_battery_pub > 0) {
- orb_publish(ORB_ID(battery_status), _battery_pub, &_battery_status);
+ } else {
+ /* mark status as invalid */
+ _battery_status.voltage_v = -1.0f;
+ _battery_status.voltage_filtered_v = -1.0f;
+ }
- } else {
- _battery_pub = orb_advertise(ORB_ID(battery_status), &_battery_status);
+ } else if (ADC_BATTERY_CURRENT_CHANNEL == buf_adc[i].am_channel) {
+ /* handle current only if voltage is valid */
+ if (_battery_status.voltage_v > 0.0f) {
+ float current = (buf_adc[i].am_data * _parameters.battery_current_scaling);
+ /* check measured current value */
+ if (current >= 0.0f) {
+ _battery_status.timestamp = t;
+ _battery_status.current_a = current;
+ if (_battery_current_timestamp != 0) {
+ /* initialize discharged value */
+ if (_battery_status.discharged_mah < 0.0f)
+ _battery_status.discharged_mah = 0.0f;
+ _battery_discharged += current * (t - _battery_current_timestamp);
+ _battery_status.discharged_mah = ((float) _battery_discharged) / 3600000.0f;
+ }
}
- }
+ }
+ _battery_current_timestamp = t;
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
/* calculate airspeed, raw is the difference from */
- float voltage = (float)(buf_adc[i].am_data ) * 3.3f / 4096.0f * 2.0f; //V_ref/4096 * (voltage divider factor)
+ float voltage = (float)(buf_adc[i].am_data) * 3.3f / 4096.0f * 2.0f; //V_ref/4096 * (voltage divider factor)
/**
* The voltage divider pulls the signal down, only act on
- * a valid voltage from a connected sensor
+ * a valid voltage from a connected sensor. Also assume a non-
+ * zero offset from the sensor if its connected.
*/
- if (voltage > 0.4f) {
+ if (voltage > 0.4f && _parameters.diff_pres_analog_enabled) {
float diff_pres_pa = voltage * 1000.0f - _parameters.diff_pres_offset_pa; //for MPXV7002DP sensor
- _diff_pres.timestamp = hrt_absolute_time();
+ _diff_pres.timestamp = t;
_diff_pres.differential_pressure_pa = diff_pres_pa;
_diff_pres.voltage = voltage;
@@ -1108,28 +1249,38 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
}
-
- _last_adc = hrt_absolute_time();
+ }
+ _last_adc = t;
+ if (_battery_status.voltage_v > 0.0f) {
+ /* announce the battery status if needed, just publish else */
+ if (_battery_pub > 0) {
+ orb_publish(ORB_ID(battery_status), _battery_pub, &_battery_status);
+
+ } else {
+ _battery_pub = orb_advertise(ORB_ID(battery_status), &_battery_status);
+ }
}
}
}
}
-#if CONFIG_HRT_PPM
void
-Sensors::ppm_poll()
+Sensors::rc_poll()
{
-
- /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
bool rc_updated;
orb_check(_rc_sub, &rc_updated);
if (rc_updated) {
+ /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
struct rc_input_values rc_input;
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
+ if (rc_input.rc_lost)
+ return;
+
struct manual_control_setpoint_s manual_control;
+ struct actuator_controls_s actuator_group_3;
/* initialize to default values */
manual_control.roll = NAN;
@@ -1137,10 +1288,11 @@ Sensors::ppm_poll()
manual_control.yaw = NAN;
manual_control.throttle = NAN;
- manual_control.manual_mode_switch = NAN;
- manual_control.manual_sas_switch = NAN;
- manual_control.return_to_launch_switch = NAN;
- manual_control.auto_offboard_input_switch = NAN;
+ manual_control.mode_switch = NAN;
+ manual_control.return_switch = NAN;
+ manual_control.assisted_switch = NAN;
+ manual_control.mission_switch = NAN;
+// manual_control.auto_offboard_input_switch = NAN;
manual_control.flaps = NAN;
manual_control.aux1 = NAN;
@@ -1153,13 +1305,25 @@ Sensors::ppm_poll()
if (rc_input.channel_count < 4)
return;
+ /* failsafe check */
+ if (_parameters.rc_fs_ch != 0) {
+ if (_parameters.rc_fs_mode == 0) {
+ if (rc_input.values[_parameters.rc_fs_ch - 1] < _parameters.rc_fs_thr)
+ return;
+
+ } else if (_parameters.rc_fs_mode == 1) {
+ if (rc_input.values[_parameters.rc_fs_ch - 1] > _parameters.rc_fs_thr)
+ return;
+ }
+ }
+
unsigned channel_limit = rc_input.channel_count;
if (channel_limit > _rc_max_chan_count)
channel_limit = _rc_max_chan_count;
/* we are accepting this message */
- _ppm_last_valid = rc_input.timestamp;
+ _rc_last_valid = rc_input.timestamp_last_signal;
/* Read out values from raw message */
for (unsigned int i = 0; i < channel_limit; i++) {
@@ -1169,6 +1333,7 @@ Sensors::ppm_poll()
*/
if (rc_input.values[i] < _parameters.min[i])
rc_input.values[i] = _parameters.min[i];
+
if (rc_input.values[i] > _parameters.max[i])
rc_input.values[i] = _parameters.max[i];
@@ -1207,9 +1372,9 @@ Sensors::ppm_poll()
}
_rc.chan_count = rc_input.channel_count;
- _rc.timestamp = rc_input.timestamp;
+ _rc.timestamp = rc_input.timestamp_last_signal;
- manual_control.timestamp = rc_input.timestamp;
+ manual_control.timestamp = rc_input.timestamp_last_signal;
/* roll input - rolling right is stick-wise and rotation-wise positive */
manual_control.roll = limit_minus_one_to_one(_rc.chan[_rc.function[ROLL]].scaled);
@@ -1240,12 +1405,6 @@ Sensors::ppm_poll()
manual_control.yaw *= _parameters.rc_scale_yaw;
}
- /* override switch input */
- manual_control.manual_override_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OVERRIDE]].scaled);
-
- /* mode switch input */
- manual_control.auto_mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[AUTO_MODE]].scaled);
-
/* flaps */
if (_rc.function[FLAPS] >= 0) {
@@ -1256,22 +1415,28 @@ Sensors::ppm_poll()
}
}
- if (_rc.function[MANUAL_MODE] >= 0) {
- manual_control.manual_mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MANUAL_MODE]].scaled);
+ if (_rc.function[MODE] >= 0) {
+ manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
}
- if (_rc.function[SAS_MODE] >= 0) {
- manual_control.manual_sas_switch = limit_minus_one_to_one(_rc.chan[_rc.function[SAS_MODE]].scaled);
+ if (_rc.function[MISSION] >= 0) {
+ manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
}
- if (_rc.function[RTL] >= 0) {
- manual_control.return_to_launch_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RTL]].scaled);
+ /* land switch input */
+ if (_rc.function[RETURN] >= 0) {
+ manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
}
- if (_rc.function[OFFBOARD_MODE] >= 0) {
- manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
+ /* assisted switch input */
+ if (_rc.function[ASSISTED] >= 0) {
+ manual_control.assisted_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ASSISTED]].scaled);
}
+// if (_rc.function[OFFBOARD_MODE] >= 0) {
+// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
+// }
+
/* aux functions, only assign if valid mapping is present */
if (_rc.function[AUX_1] >= 0) {
manual_control.aux1 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_1]].scaled);
@@ -1293,6 +1458,16 @@ Sensors::ppm_poll()
manual_control.aux5 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_5]].scaled);
}
+ /* copy from mapped manual control to control group 3 */
+ actuator_group_3.control[0] = manual_control.roll;
+ actuator_group_3.control[1] = manual_control.pitch;
+ actuator_group_3.control[2] = manual_control.yaw;
+ actuator_group_3.control[3] = manual_control.throttle;
+ actuator_group_3.control[4] = manual_control.flaps;
+ actuator_group_3.control[5] = manual_control.aux1;
+ actuator_group_3.control[6] = manual_control.aux2;
+ actuator_group_3.control[7] = manual_control.aux3;
+
/* check if ready for publishing */
if (_rc_pub > 0) {
orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc);
@@ -1309,10 +1484,17 @@ Sensors::ppm_poll()
} else {
_manual_control_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual_control);
}
+
+ /* check if ready for publishing */
+ if (_actuator_group_3_pub > 0) {
+ orb_publish(ORB_ID(actuator_controls_3), _actuator_group_3_pub, &actuator_group_3);
+
+ } else {
+ _actuator_group_3_pub = orb_advertise(ORB_ID(actuator_controls_3), &actuator_group_3);
+ }
}
}
-#endif
void
Sensors::task_main_trampoline(int argc, char *argv[])
@@ -1324,10 +1506,6 @@ void
Sensors::task_main()
{
- /* inform about start */
- printf("[sensors] Initializing..\n");
- fflush(stdout);
-
/* start individual sensors */
accel_init();
gyro_init();
@@ -1344,12 +1522,15 @@ Sensors::task_main()
_rc_sub = orb_subscribe(ORB_ID(input_rc));
_baro_sub = orb_subscribe(ORB_ID(sensor_baro));
_diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
- _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ _vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
/* rate limit vehicle status updates to 5Hz */
- orb_set_interval(_vstatus_sub, 200);
+ orb_set_interval(_vcontrol_mode_sub, 200);
+
+ /* rate limit gyro to 250 Hz (the gyro signal is lowpassed accordingly earlier) */
+ orb_set_interval(_gyro_sub, 4);
/*
* do advertisements
@@ -1363,7 +1544,10 @@ Sensors::task_main()
raw.adc_voltage_v[3] = 0.0f;
memset(&_battery_status, 0, sizeof(_battery_status));
- _battery_status.voltage_v = BAT_VOL_INITIAL;
+ _battery_status.voltage_v = -1.0f;
+ _battery_status.voltage_filtered_v = -1.0f;
+ _battery_status.current_a = -1.0f;
+ _battery_status.discharged_mah = -1.0f;
/* get a set of initial values */
accel_poll(raw);
@@ -1386,7 +1570,7 @@ Sensors::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. */
@@ -1402,7 +1586,7 @@ Sensors::task_main()
perf_begin(_loop_perf);
/* check vehicle status for changes to publication state */
- vehicle_status_poll();
+ vehicle_control_mode_poll();
/* check parameters for updates */
parameter_update_poll();
@@ -1425,10 +1609,8 @@ Sensors::task_main()
if (_publishing)
orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw);
-#ifdef CONFIG_HRT_PPM
/* Look for new r/c input data */
- ppm_poll();
-#endif
+ rc_poll();
perf_end(_loop_perf);
}
@@ -1446,11 +1628,11 @@ Sensors::start()
/* start the task */
_sensors_task = task_spawn_cmd("sensors_task",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Sensors::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Sensors::task_main_trampoline,
+ nullptr);
if (_sensors_task < 0) {
warn("task start failed");
@@ -1468,7 +1650,7 @@ int sensors_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (sensors::g_sensors != nullptr)
- errx(1, "sensors task already running");
+ errx(0, "sensors task already running");
sensors::g_sensors = new Sensors;
@@ -1502,6 +1684,7 @@ int sensors_main(int argc, char *argv[])
}
}
- errx(1, "unrecognized command");
+ warnx("unrecognized command");
+ return 1;
}
diff --git a/src/modules/systemlib/airspeed.c b/src/modules/systemlib/airspeed.c
index 15bb833a9..1a479c205 100644
--- a/src/modules/systemlib/airspeed.c
+++ b/src/modules/systemlib/airspeed.c
@@ -42,7 +42,7 @@
#include <stdio.h>
#include <math.h>
-#include "conversions.h"
+#include <geo/geo.h>
#include "airspeed.h"
@@ -59,10 +59,10 @@
float calc_indicated_airspeed(float differential_pressure)
{
- if (differential_pressure > 0) {
+ if (differential_pressure > 0.0f) {
return sqrtf((2.0f*differential_pressure) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
} else {
- return -sqrtf((2.0f*fabs(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
+ return -sqrtf((2.0f*fabsf(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
}
}
@@ -95,17 +95,21 @@ float calc_true_airspeed_from_indicated(float speed_indicated, float pressure_am
float calc_true_airspeed(float total_pressure, float static_pressure, float temperature_celsius)
{
float density = get_air_density(static_pressure, temperature_celsius);
+
if (density < 0.0001f || !isfinite(density)) {
- density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
-// printf("[airspeed] Invalid air density, using density at sea level\n");
+ density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
}
float pressure_difference = total_pressure - static_pressure;
- if(pressure_difference > 0) {
+ if (pressure_difference > 0) {
return sqrtf((2.0f*(pressure_difference)) / density);
- } else
- {
- return -sqrtf((2.0f*fabs(pressure_difference)) / density);
+ } else {
+ return -sqrtf((2.0f*fabsf(pressure_difference)) / density);
}
}
+
+float get_air_density(float static_pressure, float temperature_celsius)
+{
+ return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS));
+}
diff --git a/src/modules/systemlib/airspeed.h b/src/modules/systemlib/airspeed.h
index def53f0c1..8dccaab9c 100644
--- a/src/modules/systemlib/airspeed.h
+++ b/src/modules/systemlib/airspeed.h
@@ -85,6 +85,14 @@
*/
__EXPORT float calc_true_airspeed(float total_pressure, float static_pressure, float temperature_celsius);
+ /**
+ * Calculates air density.
+ *
+ * @param static_pressure ambient pressure in millibar
+ * @param temperature_celcius air / ambient temperature in celcius
+ */
+__EXPORT float get_air_density(float static_pressure, float temperature_celsius);
+
__END_DECLS
#endif
diff --git a/src/modules/multirotor_pos_control/position_control.h b/src/modules/systemlib/board_serial.c
index 2144ebc34..ad8c2bf83 100644
--- a/src/modules/multirotor_pos_control/position_control.h
+++ b/src/modules/systemlib/board_serial.c
@@ -1,10 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.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
@@ -36,15 +32,29 @@
****************************************************************************/
/**
- * @file multirotor_position_control.h
- * Definition of the position control for a multirotor VTOL
+ * @file board_serial.h
+ * Read off the board serial
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author David "Buzz" Bussenschutt <davidbuzz@gmail.com>
+ *
*/
-// #ifndef POSITION_CONTROL_H_
-// #define POSITION_CONTROL_H_
+#include "otp.h"
+#include "board_config.h"
+#include "board_serial.h"
+
+int get_board_serial(char *serialid)
+{
+ const volatile unsigned *udid_ptr = (const unsigned *)UDID_START;
+ union udid id;
+ val_read((unsigned *)&id, udid_ptr, sizeof(id));
+
-// void control_multirotor_position(const struct vehicle_state_s *vstatus, const struct vehicle_manual_control_s *manual,
-// const struct vehicle_attitude_s *att, const struct vehicle_local_position_s *local_pos,
-// const struct vehicle_local_position_setpoint_s *local_pos_sp, struct vehicle_attitude_setpoint_s *att_sp);
+ /* Copy the serial from the chips non-write memory and swap endianess */
+ serialid[0] = id.data[3]; serialid[1] = id.data[2]; serialid[2] = id.data[1]; serialid[3] = id.data[0];
+ serialid[4] = id.data[7]; serialid[5] = id.data[6]; serialid[6] = id.data[5]; serialid[7] = id.data[4];
+ serialid[8] = id.data[11]; serialid[9] = id.data[10]; serialid[10] = id.data[9]; serialid[11] = id.data[8];
-// #endif /* POSITION_CONTROL_H_ */
+ return 0;
+} \ No newline at end of file
diff --git a/src/modules/systemlib/board_serial.h b/src/modules/systemlib/board_serial.h
new file mode 100644
index 000000000..b14bb4376
--- /dev/null
+++ b/src/modules/systemlib/board_serial.h
@@ -0,0 +1,49 @@
+/****************************************************************************
+ *
+ * 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 board_serial.h
+ * Read off the board serial
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author David "Buzz" Bussenschutt <davidbuzz@gmail.com>
+ *
+ */
+
+#pragma once
+
+__BEGIN_DECLS
+
+__EXPORT int get_board_serial(char *serialid);
+
+__END_DECLS
diff --git a/src/modules/systemlib/bson/tinybson.c b/src/modules/systemlib/bson/tinybson.c
index 8aca6a25d..49403c98b 100644
--- a/src/modules/systemlib/bson/tinybson.c
+++ b/src/modules/systemlib/bson/tinybson.c
@@ -407,6 +407,9 @@ bson_encoder_fini(bson_encoder_t encoder)
memcpy(encoder->buf, &len, sizeof(len));
}
+ /* sync file */
+ fsync(encoder->fd);
+
return 0;
}
diff --git a/src/modules/systemlib/conversions.c b/src/modules/systemlib/conversions.c
index ac94252c5..9105d83cb 100644
--- a/src/modules/systemlib/conversions.c
+++ b/src/modules/systemlib/conversions.c
@@ -55,100 +55,3 @@ int16_t_from_bytes(uint8_t bytes[])
return u.w;
}
-
-void rot2quat(const float R[9], float Q[4])
-{
- float q0_2;
- float q1_2;
- float q2_2;
- float q3_2;
- int32_t idx;
-
- /* conversion of rotation matrix to quaternion
- * choose the largest component to begin with */
- q0_2 = (((1.0F + R[0]) + R[4]) + R[8]) / 4.0F;
- q1_2 = (((1.0F + R[0]) - R[4]) - R[8]) / 4.0F;
- q2_2 = (((1.0F - R[0]) + R[4]) - R[8]) / 4.0F;
- q3_2 = (((1.0F - R[0]) - R[4]) + R[8]) / 4.0F;
-
- idx = 0;
-
- if (q0_2 < q1_2) {
- q0_2 = q1_2;
-
- idx = 1;
- }
-
- if (q0_2 < q2_2) {
- q0_2 = q2_2;
- idx = 2;
- }
-
- if (q0_2 < q3_2) {
- q0_2 = q3_2;
- idx = 3;
- }
-
- q0_2 = sqrtf(q0_2);
-
- /* solve for the remaining three components */
- if (idx == 0) {
- q1_2 = q0_2;
- q2_2 = (R[5] - R[7]) / 4.0F / q0_2;
- q3_2 = (R[6] - R[2]) / 4.0F / q0_2;
- q0_2 = (R[1] - R[3]) / 4.0F / q0_2;
-
- } else if (idx == 1) {
- q2_2 = q0_2;
- q1_2 = (R[5] - R[7]) / 4.0F / q0_2;
- q3_2 = (R[3] + R[1]) / 4.0F / q0_2;
- q0_2 = (R[6] + R[2]) / 4.0F / q0_2;
-
- } else if (idx == 2) {
- q3_2 = q0_2;
- q1_2 = (R[6] - R[2]) / 4.0F / q0_2;
- q2_2 = (R[3] + R[1]) / 4.0F / q0_2;
- q0_2 = (R[7] + R[5]) / 4.0F / q0_2;
-
- } else {
- q1_2 = (R[1] - R[3]) / 4.0F / q0_2;
- q2_2 = (R[6] + R[2]) / 4.0F / q0_2;
- q3_2 = (R[7] + R[5]) / 4.0F / q0_2;
- }
-
- /* return values */
- Q[0] = q1_2;
- Q[1] = q2_2;
- Q[2] = q3_2;
- Q[3] = q0_2;
-}
-
-void quat2rot(const float Q[4], float R[9])
-{
- float q0_2;
- float q1_2;
- float q2_2;
- float q3_2;
-
- memset(&R[0], 0, 9U * sizeof(float));
-
- q0_2 = Q[0] * Q[0];
- q1_2 = Q[1] * Q[1];
- q2_2 = Q[2] * Q[2];
- q3_2 = Q[3] * Q[3];
-
- R[0] = ((q0_2 + q1_2) - q2_2) - q3_2;
- R[3] = 2.0F * (Q[1] * Q[2] - Q[0] * Q[3]);
- R[6] = 2.0F * (Q[1] * Q[3] + Q[0] * Q[2]);
- R[1] = 2.0F * (Q[1] * Q[2] + Q[0] * Q[3]);
- R[4] = ((q0_2 + q2_2) - q1_2) - q3_2;
- R[7] = 2.0F * (Q[2] * Q[3] - Q[0] * Q[1]);
- R[2] = 2.0F * (Q[1] * Q[3] - Q[0] * Q[2]);
- R[5] = 2.0F * (Q[2] * Q[3] + Q[0] * Q[1]);
- R[8] = ((q0_2 + q3_2) - q1_2) - q2_2;
-}
-
-float get_air_density(float static_pressure, float temperature_celsius)
-{
- return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS));
-}
diff --git a/src/modules/systemlib/conversions.h b/src/modules/systemlib/conversions.h
index 5d485b01f..dc383e770 100644
--- a/src/modules/systemlib/conversions.h
+++ b/src/modules/systemlib/conversions.h
@@ -44,11 +44,6 @@
#include <float.h>
#include <stdint.h>
-#define CONSTANTS_ONE_G 9.80665f // m/s^2
-#define CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C 1.225f // kg/m^3
-#define CONSTANTS_AIR_GAS_CONST 287.1f // J/(kg * K)
-#define CONSTANTS_ABSOLUTE_NULL_CELSIUS -273.15f // °C
-
__BEGIN_DECLS
/**
@@ -61,34 +56,6 @@ __BEGIN_DECLS
*/
__EXPORT int16_t int16_t_from_bytes(uint8_t bytes[]);
-/**
- * Converts a 3 x 3 rotation matrix to an unit quaternion.
- *
- * All orientations are expressed in NED frame.
- *
- * @param R rotation matrix to convert
- * @param Q quaternion to write back to
- */
-__EXPORT void rot2quat(const float R[9], float Q[4]);
-
-/**
- * Converts an unit quaternion to a 3 x 3 rotation matrix.
- *
- * All orientations are expressed in NED frame.
- *
- * @param Q quaternion to convert
- * @param R rotation matrix to write back to
- */
-__EXPORT void quat2rot(const float Q[4], float R[9]);
-
-/**
- * Calculates air density.
- *
- * @param static_pressure ambient pressure in millibar
- * @param temperature_celcius air / ambient temperature in celcius
- */
-__EXPORT float get_air_density(float static_pressure, float temperature_celsius);
-
__END_DECLS
#endif /* CONVERSIONS_H_ */
diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c
index 8fdff8ac0..ccc516f39 100644
--- a/src/modules/systemlib/cpuload.c
+++ b/src/modules/systemlib/cpuload.c
@@ -71,8 +71,6 @@ extern FAR struct _TCB *sched_gettcb(pid_t pid);
void cpuload_initialize_once()
{
-// if (!system_load.initialized)
-// {
system_load.start_time = hrt_absolute_time();
int i;
@@ -80,27 +78,28 @@ void cpuload_initialize_once()
system_load.tasks[i].valid = false;
}
- system_load.total_count = 0;
-
uint64_t now = hrt_absolute_time();
- /* initialize idle thread statically */
- system_load.tasks[0].start_time = now;
- system_load.tasks[0].total_runtime = 0;
- system_load.tasks[0].curr_start_time = 0;
- system_load.tasks[0].tcb = sched_gettcb(0);
- system_load.tasks[0].valid = true;
- system_load.total_count++;
-
- /* initialize init thread statically */
- system_load.tasks[1].start_time = now;
- system_load.tasks[1].total_runtime = 0;
- system_load.tasks[1].curr_start_time = 0;
- system_load.tasks[1].tcb = sched_gettcb(1);
- system_load.tasks[1].valid = true;
- /* count init thread */
- system_load.total_count++;
- // }
+ int static_tasks_count = 2; // there are at least 2 threads that should be initialized statically - "idle" and "init"
+
+#ifdef CONFIG_PAGING
+ static_tasks_count++; // include paging thread in initialization
+#endif /* CONFIG_PAGING */
+#if CONFIG_SCHED_WORKQUEUE
+ static_tasks_count++; // include high priority work0 thread in initialization
+#endif /* CONFIG_SCHED_WORKQUEUE */
+#if CONFIG_SCHED_LPWORK
+ static_tasks_count++; // include low priority work1 thread in initialization
+#endif /* CONFIG_SCHED_WORKQUEUE */
+
+ // perform static initialization of "system" threads
+ for (system_load.total_count = 0; system_load.total_count < static_tasks_count; system_load.total_count++) {
+ system_load.tasks[system_load.total_count].start_time = now;
+ system_load.tasks[system_load.total_count].total_runtime = 0;
+ system_load.tasks[system_load.total_count].curr_start_time = 0;
+ system_load.tasks[system_load.total_count].tcb = sched_gettcb(system_load.total_count); // it is assumed that these static threads have consecutive PIDs
+ system_load.tasks[system_load.total_count].valid = true;
+ }
}
void sched_note_start(FAR struct tcb_s *tcb)
diff --git a/src/modules/systemlib/cpuload.h b/src/modules/systemlib/cpuload.h
index c7aa18d3c..16d132fdb 100644
--- a/src/modules/systemlib/cpuload.h
+++ b/src/modules/systemlib/cpuload.h
@@ -40,15 +40,15 @@ __BEGIN_DECLS
#include <nuttx/sched.h>
struct system_load_taskinfo_s {
- uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
- uint64_t curr_start_time; ///< Start time of the current scheduling slot
- uint64_t start_time; ///< FIRST start time of task
- FAR struct tcb_s *tcb; ///<
- bool valid; ///< Task is currently active / valid
+ uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
+ uint64_t curr_start_time; ///< Start time of the current scheduling slot
+ uint64_t start_time; ///< FIRST start time of task
+ FAR struct tcb_s *tcb; ///<
+ bool valid; ///< Task is currently active / valid
};
struct system_load_s {
- uint64_t start_time; ///< Global start time of measurements
+ uint64_t start_time; ///< Global start time of measurements
struct system_load_taskinfo_s tasks[CONFIG_MAX_TASKS];
uint8_t initialized;
int total_count;
diff --git a/src/modules/systemlib/geo/geo.c b/src/modules/systemlib/geo/geo.c
deleted file mode 100644
index 6746e8ff3..000000000
--- a/src/modules/systemlib/geo/geo.c
+++ /dev/null
@@ -1,439 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- *
- * 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 geo.c
- *
- * Geo / math functions to perform geodesic calculations
- *
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- */
-
-#include <systemlib/geo/geo.h>
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <pthread.h>
-#include <stdio.h>
-#include <math.h>
-#include <stdbool.h>
-
-
-/* values for map projection */
-static double phi_1;
-static double sin_phi_1;
-static double cos_phi_1;
-static double lambda_0;
-static double scale;
-
-__EXPORT void map_projection_init(double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
-{
- /* notation and formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- phi_1 = lat_0 / 180.0 * M_PI;
- lambda_0 = lon_0 / 180.0 * M_PI;
-
- sin_phi_1 = sin(phi_1);
- cos_phi_1 = cos(phi_1);
-
- /* calculate local scale by using the relation of true distance and the distance on plane */ //TODO: this is a quick solution, there are probably easier ways to determine the scale
-
- /* 1) calculate true distance d on sphere to a point: http://www.movable-type.co.uk/scripts/latlong.html */
- const double r_earth = 6371000;
-
- double lat1 = phi_1;
- double lon1 = lambda_0;
-
- double lat2 = phi_1 + 0.5 / 180 * M_PI;
- double lon2 = lambda_0 + 0.5 / 180 * M_PI;
- double sin_lat_2 = sin(lat2);
- double cos_lat_2 = cos(lat2);
- double d = acos(sin(lat1) * sin_lat_2 + cos(lat1) * cos_lat_2 * cos(lon2 - lon1)) * r_earth;
-
- /* 2) calculate distance rho on plane */
- double k_bar = 0;
- double c = acos(sin_phi_1 * sin_lat_2 + cos_phi_1 * cos_lat_2 * cos(lon2 - lambda_0));
-
- if (0 != c)
- k_bar = c / sin(c);
-
- double x2 = k_bar * (cos_lat_2 * sin(lon2 - lambda_0)); //Projection of point 2 on plane
- double y2 = k_bar * ((cos_phi_1 * sin_lat_2 - sin_phi_1 * cos_lat_2 * cos(lon2 - lambda_0)));
- double rho = sqrt(pow(x2, 2) + pow(y2, 2));
-
- scale = d / rho;
-
-}
-
-__EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
-{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- double phi = lat / 180.0 * M_PI;
- double lambda = lon / 180.0 * M_PI;
-
- double sin_phi = sin(phi);
- double cos_phi = cos(phi);
-
- double k_bar = 0;
- /* using small angle approximation (formula in comment is without aproximation) */
- double c = acos(sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2)); //double c = acos( sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * cos(lambda - lambda_0) );
-
- if (0 != c)
- k_bar = c / sin(c);
-
- /* using small angle approximation (formula in comment is without aproximation) */
- *y = k_bar * (cos_phi * (lambda - lambda_0)) * scale;//*y = k_bar * (cos_phi * sin(lambda - lambda_0)) * scale;
- *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2))) * scale; // *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * cos(lambda - lambda_0))) * scale;
-
-// printf("%phi_1=%.10f, lambda_0 =%.10f\n", phi_1, lambda_0);
-}
-
-__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon)
-{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
-
- double x_descaled = x / scale;
- double y_descaled = y / scale;
-
- double c = sqrt(pow(x_descaled, 2) + pow(y_descaled, 2));
- double sin_c = sin(c);
- double cos_c = cos(c);
-
- double lat_sphere = 0;
-
- if (c != 0)
- lat_sphere = asin(cos_c * sin_phi_1 + (x_descaled * sin_c * cos_phi_1) / c);
- else
- lat_sphere = asin(cos_c * sin_phi_1);
-
-// printf("lat_sphere = %.10f\n",lat_sphere);
-
- double lon_sphere = 0;
-
- if (phi_1 == M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 - y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(-y_descaled, x_descaled));
-
- } else if (phi_1 == -M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 + y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(y_descaled, x_descaled));
-
- } else {
-
- lon_sphere = (lambda_0 + atan2(y_descaled * sin_c , c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c));
- //using small angle approximation
-// double denominator = (c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c);
-// if(denominator != 0)
-// {
-// lon_sphere = (lambda_0 + (y_descaled * sin_c) / denominator);
-// }
-// else
-// {
-// ...
-// }
- }
-
-// printf("lon_sphere = %.10f\n",lon_sphere);
-
- *lat = lat_sphere * 180.0 / M_PI;
- *lon = lon_sphere * 180.0 / M_PI;
-
-}
-
-
-__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
-{
- double lat_now_rad = lat_now / 180.0d * M_PI;
- double lon_now_rad = lon_now / 180.0d * M_PI;
- double lat_next_rad = lat_next / 180.0d * M_PI;
- double lon_next_rad = lon_next / 180.0d * M_PI;
-
-
- double d_lat = lat_next_rad - lat_now_rad;
- double d_lon = lon_next_rad - lon_now_rad;
-
- double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
- double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a));
-
- const double radius_earth = 6371000.0d;
-
- return radius_earth * c;
-}
-
-__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
-{
- double lat_now_rad = lat_now * M_DEG_TO_RAD;
- double lon_now_rad = lon_now * M_DEG_TO_RAD;
- double lat_next_rad = lat_next * M_DEG_TO_RAD;
- double lon_next_rad = lon_next * M_DEG_TO_RAD;
-
- double d_lat = lat_next_rad - lat_now_rad;
- double d_lon = lon_next_rad - lon_now_rad;
-
- /* conscious mix of double and float trig function to maximize speed and efficiency */
- float theta = atan2f(sin(d_lon) * cos(lat_next_rad) , cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon));
-
- theta = _wrap_pi(theta);
-
- return theta;
-}
-
-// Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
-
-__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
-{
-// This function returns the distance to the nearest point on the track line. Distance is positive if current
-// position is right of the track and negative if left of the track as seen from a point on the track line
-// headed towards the end point.
-
- float dist_to_end;
- float bearing_end;
- float bearing_track;
- float bearing_diff;
-
- int return_value = ERROR; // Set error flag, cleared when valid result calculated.
- crosstrack_error->past_end = false;
- crosstrack_error->distance = 0.0f;
- crosstrack_error->bearing = 0.0f;
-
- // Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) return return_value;
-
- 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);
- bearing_diff = bearing_track - bearing_end;
- bearing_diff = _wrap_pi(bearing_diff);
-
- // Return past_end = true if past end point of line
- if (bearing_diff > M_PI_2_F || bearing_diff < -M_PI_2_F) {
- crosstrack_error->past_end = true;
- return_value = OK;
- 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) * sin(bearing_diff);
-
- if (sin(bearing_diff) >= 0) {
- crosstrack_error->bearing = _wrap_pi(bearing_track - M_PI_2_F);
-
- } else {
- crosstrack_error->bearing = _wrap_pi(bearing_track + M_PI_2_F);
- }
-
- return_value = OK;
-
- return return_value;
-
-}
-
-
-__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
- float radius, float arc_start_bearing, float arc_sweep)
-{
- // This function returns the distance to the nearest point on the track arc. Distance is positive if current
- // position is right of the arc and negative if left of the arc as seen from the closest point on the arc and
- // headed towards the end point.
-
- // Determine if the current position is inside or outside the sector between the line from the center
- // to the arc start and the line from the center to the arc end
- float bearing_sector_start;
- float bearing_sector_end;
- float bearing_now = get_bearing_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
- bool in_sector;
-
- int return_value = ERROR; // Set error flag, cleared when valid result calculated.
- crosstrack_error->past_end = false;
- crosstrack_error->distance = 0.0f;
- crosstrack_error->bearing = 0.0f;
-
- // Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) return return_value;
-
-
- if (arc_sweep >= 0) {
- bearing_sector_start = arc_start_bearing;
- bearing_sector_end = arc_start_bearing + arc_sweep;
-
- if (bearing_sector_end > 2.0f * M_PI_F) bearing_sector_end -= M_TWOPI_F;
-
- } else {
- bearing_sector_end = arc_start_bearing;
- bearing_sector_start = arc_start_bearing - arc_sweep;
-
- if (bearing_sector_start < 0.0f) bearing_sector_start += M_TWOPI_F;
- }
-
- in_sector = false;
-
- // Case where sector does not span zero
- if (bearing_sector_end >= bearing_sector_start && bearing_now >= bearing_sector_start && bearing_now <= bearing_sector_end) in_sector = true;
-
- // Case where sector does span zero
- if (bearing_sector_end < bearing_sector_start && (bearing_now > bearing_sector_start || bearing_now < bearing_sector_end)) in_sector = true;
-
- // If in the sector then calculate distance and bearing to closest point
- if (in_sector) {
- crosstrack_error->past_end = false;
- float dist_to_center = get_distance_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
-
- if (dist_to_center <= radius) {
- crosstrack_error->distance = radius - dist_to_center;
- crosstrack_error->bearing = bearing_now + M_PI_F;
-
- } else {
- crosstrack_error->distance = dist_to_center - radius;
- crosstrack_error->bearing = bearing_now;
- }
-
- // If out of the sector then calculate dist and bearing to start or end point
-
- } else {
-
- // Use the approximation that 111,111 meters in the y direction is 1 degree (of latitude)
- // and 111,111 * cos(latitude) meters in the x direction is 1 degree (of longitude) to
- // calculate the position of the start and end points. We should not be doing this often
- // as this function generally will not be called repeatedly when we are out of the sector.
-
- // TO DO - this is messed up and won't compile
- float start_disp_x = radius * sin(arc_start_bearing);
- float start_disp_y = radius * cos(arc_start_bearing);
- float end_disp_x = radius * sin(_wrapPI(arc_start_bearing + arc_sweep));
- float end_disp_y = radius * cos(_wrapPI(arc_start_bearing + arc_sweep));
- float lon_start = lon_now + start_disp_x / 111111.0d;
- float lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0d;
- float lon_end = lon_now + end_disp_x / 111111.0d;
- float lat_end = lat_now + end_disp_y * cos(lat_now) / 111111.0d;
- float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
- float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
-
-
- if (dist_to_start < dist_to_end) {
- crosstrack_error->distance = dist_to_start;
- crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
-
- } else {
- crosstrack_error->past_end = true;
- crosstrack_error->distance = dist_to_end;
- crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
- }
-
- }
-
- crosstrack_error->bearing = _wrapPI(crosstrack_error->bearing);
- return_value = OK;
- return return_value;
-}
-
-__EXPORT float _wrap_pi(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing) || bearing == 0) {
- return bearing;
- }
-
- int c = 0;
-
- while (bearing > M_PI_F && c < 30) {
- bearing -= M_TWOPI_F;
- c++;
- }
-
- c = 0;
-
- while (bearing <= -M_PI_F && c < 30) {
- bearing += M_TWOPI_F;
- c++;
- }
-
- return bearing;
-}
-
-__EXPORT float _wrap_2pi(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing)) {
- return bearing;
- }
-
- while (bearing >= M_TWOPI_F) {
- bearing = bearing - M_TWOPI_F;
- }
-
- while (bearing < 0.0f) {
- bearing = bearing + M_TWOPI_F;
- }
-
- return bearing;
-}
-
-__EXPORT float _wrap_180(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing)) {
- return bearing;
- }
-
- while (bearing > 180.0f) {
- bearing = bearing - 360.0f;
- }
-
- while (bearing <= -180.0f) {
- bearing = bearing + 360.0f;
- }
-
- return bearing;
-}
-
-__EXPORT float _wrap_360(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing)) {
- return bearing;
- }
-
- while (bearing >= 360.0f) {
- bearing = bearing - 360.0f;
- }
-
- while (bearing < 0.0f) {
- bearing = bearing + 360.0f;
- }
-
- return bearing;
-}
-
-
diff --git a/src/modules/systemlib/geo/geo.h b/src/modules/systemlib/geo/geo.h
deleted file mode 100644
index 0c0b5c533..000000000
--- a/src/modules/systemlib/geo/geo.h
+++ /dev/null
@@ -1,97 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- *
- * 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 geo.h
- *
- * Definition of geo / math functions to perform geodesic calculations
- *
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
- */
-
-
-#include <stdbool.h>
-
-struct crosstrack_error_s {
- bool past_end; // Flag indicating we are past the end of the line/arc segment
- float distance; // Distance in meters to closest point on line/arc
- float bearing; // Bearing in radians to closest point on line/arc
-} ;
-
-/**
- * Initializes the 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 void map_projection_init(double lat_0, double lon_0);
-
-/**
- * Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
- * @param x north
- * @param y east
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT void map_projection_project(double lat, double lon, float *x, float *y);
-
-/**
- * Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
- *
- * @param x north
- * @param y east
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon);
-
-__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-
-__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-
-__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
-
-__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
- float radius, float arc_start_bearing, float arc_sweep);
-
-__EXPORT float _wrap_180(float bearing);
-__EXPORT float _wrap_360(float bearing);
-__EXPORT float _wrap_pi(float bearing);
-__EXPORT float _wrap_2pi(float bearing);
diff --git a/src/modules/systemlib/hx_stream.c b/src/modules/systemlib/hx_stream.c
index 8d77f14a8..8e9c2bfcf 100644
--- a/src/modules/systemlib/hx_stream.c
+++ b/src/modules/systemlib/hx_stream.c
@@ -53,14 +53,26 @@
struct hx_stream {
- uint8_t buf[HX_STREAM_MAX_FRAME + 4];
- unsigned frame_bytes;
- bool escaped;
- bool txerror;
-
+ /* RX state */
+ uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4];
+ unsigned rx_frame_bytes;
+ bool rx_escaped;
+ hx_stream_rx_callback rx_callback;
+ void *rx_callback_arg;
+
+ /* TX state */
int fd;
- hx_stream_rx_callback callback;
- void *callback_arg;
+ bool tx_error;
+ uint8_t *tx_buf;
+ unsigned tx_resid;
+ uint32_t tx_crc;
+ enum {
+ TX_IDLE = 0,
+ TX_SEND_START,
+ TX_SEND_DATA,
+ TX_SENT_ESCAPE,
+ TX_SEND_END
+ } tx_state;
perf_counter_t pc_tx_frames;
perf_counter_t pc_rx_frames;
@@ -81,21 +93,7 @@ static void
hx_tx_raw(hx_stream_t stream, uint8_t c)
{
if (write(stream->fd, &c, 1) != 1)
- stream->txerror = true;
-}
-
-static void
-hx_tx_byte(hx_stream_t stream, uint8_t c)
-{
- switch (c) {
- case FBO:
- case CEO:
- hx_tx_raw(stream, CEO);
- c ^= 0x20;
- break;
- }
-
- hx_tx_raw(stream, c);
+ stream->tx_error = true;
}
static int
@@ -105,11 +103,11 @@ hx_rx_frame(hx_stream_t stream)
uint8_t b[4];
uint32_t w;
} u;
- unsigned length = stream->frame_bytes;
+ unsigned length = stream->rx_frame_bytes;
/* reset the stream */
- stream->frame_bytes = 0;
- stream->escaped = false;
+ stream->rx_frame_bytes = 0;
+ stream->rx_escaped = false;
/* not a real frame - too short */
if (length < 4) {
@@ -122,11 +120,11 @@ hx_rx_frame(hx_stream_t stream)
length -= 4;
/* compute expected CRC */
- u.w = crc32(&stream->buf[0], length);
+ u.w = crc32(&stream->rx_buf[0], length);
/* compare computed and actual CRC */
for (unsigned i = 0; i < 4; i++) {
- if (u.b[i] != stream->buf[length + i]) {
+ if (u.b[i] != stream->rx_buf[length + i]) {
perf_count(stream->pc_rx_errors);
return 0;
}
@@ -134,7 +132,7 @@ hx_rx_frame(hx_stream_t stream)
/* frame is good */
perf_count(stream->pc_rx_frames);
- stream->callback(stream->callback_arg, &stream->buf[0], length);
+ stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length);
return 1;
}
@@ -150,8 +148,8 @@ hx_stream_init(int fd,
if (stream != NULL) {
memset(stream, 0, sizeof(struct hx_stream));
stream->fd = fd;
- stream->callback = callback;
- stream->callback_arg = arg;
+ stream->rx_callback = callback;
+ stream->rx_callback_arg = arg;
}
return stream;
@@ -179,49 +177,112 @@ hx_stream_set_counters(hx_stream_t stream,
stream->pc_rx_errors = rx_errors;
}
+void
+hx_stream_reset(hx_stream_t stream)
+{
+ stream->rx_frame_bytes = 0;
+ stream->rx_escaped = false;
+
+ stream->tx_buf = NULL;
+ stream->tx_resid = 0;
+ stream->tx_state = TX_IDLE;
+}
+
int
-hx_stream_send(hx_stream_t stream,
+hx_stream_start(hx_stream_t stream,
const void *data,
size_t count)
{
- union {
- uint8_t b[4];
- uint32_t w;
- } u;
- const uint8_t *p = (const uint8_t *)data;
- unsigned resid = count;
-
- if (resid > HX_STREAM_MAX_FRAME)
+ if (count > HX_STREAM_MAX_FRAME)
return -EINVAL;
- /* start the frame */
- hx_tx_raw(stream, FBO);
+ stream->tx_buf = data;
+ stream->tx_resid = count;
+ stream->tx_state = TX_SEND_START;
+ stream->tx_crc = crc32(data, count);
+ return OK;
+}
+
+int
+hx_stream_send_next(hx_stream_t stream)
+{
+ int c;
+
+ /* sort out what we're going to send */
+ switch (stream->tx_state) {
- /* transmit the data */
- while (resid--)
- hx_tx_byte(stream, *p++);
+ case TX_SEND_START:
+ stream->tx_state = TX_SEND_DATA;
+ return FBO;
- /* compute the CRC */
- u.w = crc32(data, count);
+ case TX_SEND_DATA:
+ c = *stream->tx_buf;
- /* send the CRC */
- p = &u.b[0];
- resid = 4;
+ switch (c) {
+ case FBO:
+ case CEO:
+ stream->tx_state = TX_SENT_ESCAPE;
+ return CEO;
+ }
+ break;
+
+ case TX_SENT_ESCAPE:
+ c = *stream->tx_buf ^ 0x20;
+ stream->tx_state = TX_SEND_DATA;
+ break;
+
+ case TX_SEND_END:
+ stream->tx_state = TX_IDLE;
+ return FBO;
+
+ case TX_IDLE:
+ default:
+ return -1;
+ }
+
+ /* if we are here, we have consumed a byte from the buffer */
+ stream->tx_resid--;
+ stream->tx_buf++;
+
+ /* buffer exhausted */
+ if (stream->tx_resid == 0) {
+ uint8_t *pcrc = (uint8_t *)&stream->tx_crc;
+
+ /* was the buffer the frame CRC? */
+ if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) {
+ stream->tx_state = TX_SEND_END;
+ } else {
+ /* no, it was the payload - switch to sending the CRC */
+ stream->tx_buf = pcrc;
+ stream->tx_resid = sizeof(stream->tx_crc);
+ }
+ }
+ return c;
+}
+
+int
+hx_stream_send(hx_stream_t stream,
+ const void *data,
+ size_t count)
+{
+ int result;
- while (resid--)
- hx_tx_byte(stream, *p++);
+ result = hx_stream_start(stream, data, count);
+ if (result != OK)
+ return result;
- /* and the trailing frame separator */
- hx_tx_raw(stream, FBO);
+ int c;
+ while ((c = hx_stream_send_next(stream)) >= 0)
+ hx_tx_raw(stream, c);
/* check for transmit error */
- if (stream->txerror) {
- stream->txerror = false;
+ if (stream->tx_error) {
+ stream->tx_error = false;
return -EIO;
}
perf_count(stream->pc_tx_frames);
- return 0;
+ return OK;
}
void
@@ -234,17 +295,17 @@ hx_stream_rx(hx_stream_t stream, uint8_t c)
}
/* escaped? */
- if (stream->escaped) {
- stream->escaped = false;
+ if (stream->rx_escaped) {
+ stream->rx_escaped = false;
c ^= 0x20;
} else if (c == CEO) {
- /* now escaped, ignore the byte */
- stream->escaped = true;
+ /* now rx_escaped, ignore the byte */
+ stream->rx_escaped = true;
return;
}
/* save for later */
- if (stream->frame_bytes < sizeof(stream->buf))
- stream->buf[stream->frame_bytes++] = c;
+ if (stream->rx_frame_bytes < sizeof(stream->rx_buf))
+ stream->rx_buf[stream->rx_frame_bytes++] = c;
}
diff --git a/src/modules/systemlib/hx_stream.h b/src/modules/systemlib/hx_stream.h
index 128689953..1f3927222 100644
--- a/src/modules/systemlib/hx_stream.h
+++ b/src/modules/systemlib/hx_stream.h
@@ -58,7 +58,8 @@ __BEGIN_DECLS
* Allocate a new hx_stream object.
*
* @param fd The file handle over which the protocol will
- * communicate.
+ * communicate, or -1 if the protocol will use
+ * hx_stream_start/hx_stream_send_next.
* @param callback Called when a frame is received.
* @param callback_arg Passed to the callback.
* @return A handle to the stream, or NULL if memory could
@@ -80,6 +81,7 @@ __EXPORT extern void hx_stream_free(hx_stream_t stream);
*
* Any counter may be set to NULL to disable counting that datum.
*
+ * @param stream A handle returned from hx_stream_init.
* @param tx_frames Counter for transmitted frames.
* @param rx_frames Counter for received frames.
* @param rx_errors Counter for short and corrupt received frames.
@@ -90,6 +92,44 @@ __EXPORT extern void hx_stream_set_counters(hx_stream_t stream,
perf_counter_t rx_errors);
/**
+ * Reset a stream.
+ *
+ * Forces the local stream state to idle.
+ *
+ * @param stream A handle returned from hx_stream_init.
+ */
+__EXPORT extern void hx_stream_reset(hx_stream_t stream);
+
+/**
+ * Prepare to send a frame.
+ *
+ * Use this in conjunction with hx_stream_send_next to
+ * set the frame to be transmitted.
+ *
+ * Use hx_stream_send() to write to the stream fd directly.
+ *
+ * @param stream A handle returned from hx_stream_init.
+ * @param data Pointer to the data to send.
+ * @param count The number of bytes to send.
+ * @return Zero on success, -errno on error.
+ */
+__EXPORT extern int hx_stream_start(hx_stream_t stream,
+ const void *data,
+ size_t count);
+
+/**
+ * Get the next byte to send for a stream.
+ *
+ * This requires that the stream be prepared for sending by
+ * calling hx_stream_start first.
+ *
+ * @param stream A handle returned from hx_stream_init.
+ * @return The byte to send, or -1 if there is
+ * nothing left to send.
+ */
+__EXPORT extern int hx_stream_send_next(hx_stream_t stream);
+
+/**
* Send a frame.
*
* This function will block until all frame bytes are sent if
diff --git a/src/modules/mavlink/mavlink_log.c b/src/modules/systemlib/mavlink_log.c
index d9416a08b..f321f9ceb 100644
--- a/src/modules/mavlink/mavlink_log.c
+++ b/src/modules/systemlib/mavlink_log.c
@@ -41,29 +41,38 @@
#include <string.h>
#include <stdlib.h>
+#include <stdio.h>
#include <stdarg.h>
#include <mavlink/mavlink_log.h>
-void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
+__EXPORT void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
{
lb->size = size;
lb->start = 0;
lb->count = 0;
- lb->elems = (struct mavlink_logmessage *)calloc(lb->size, sizeof(struct mavlink_logmessage));
+ lb->elems = calloc(lb->size, sizeof(struct mavlink_logmessage));
}
-int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
+__EXPORT void mavlink_logbuffer_destroy(struct mavlink_logbuffer *lb)
+{
+ lb->size = 0;
+ lb->start = 0;
+ lb->count = 0;
+ free(lb->elems);
+}
+
+__EXPORT int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
{
return lb->count == (int)lb->size;
}
-int mavlink_logbuffer_is_empty(struct mavlink_logbuffer *lb)
+__EXPORT int mavlink_logbuffer_is_empty(struct mavlink_logbuffer *lb)
{
return lb->count == 0;
}
-void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_logmessage *elem)
+__EXPORT void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_logmessage *elem)
{
int end = (lb->start + lb->count) % lb->size;
memcpy(&(lb->elems[end]), elem, sizeof(struct mavlink_logmessage));
@@ -76,12 +85,13 @@ void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_
}
}
-int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem)
+__EXPORT int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem)
{
if (!mavlink_logbuffer_is_empty(lb)) {
memcpy(elem, &(lb->elems[lb->start]), sizeof(struct mavlink_logmessage));
lb->start = (lb->start + 1) % lb->size;
--lb->count;
+
return 0;
} else {
@@ -89,7 +99,7 @@ int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessa
}
}
-void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...)
+__EXPORT void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
diff --git a/src/modules/systemlib/mixer/mixer.cpp b/src/modules/systemlib/mixer/mixer.cpp
index df0dfe838..cce46bf5f 100644
--- a/src/modules/systemlib/mixer/mixer.cpp
+++ b/src/modules/systemlib/mixer/mixer.cpp
@@ -50,6 +50,8 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <ctype.h>
+#include <systemlib/err.h>
#include "mixer.h"
@@ -114,6 +116,33 @@ Mixer::scale_check(struct mixer_scaler_s &scaler)
return 0;
}
+const char *
+Mixer::findtag(const char *buf, unsigned &buflen, char tag)
+{
+ while (buflen >= 2) {
+ if ((buf[0] == tag) && (buf[1] == ':'))
+ return buf;
+ buf++;
+ buflen--;
+ }
+ return nullptr;
+}
+
+const char *
+Mixer::skipline(const char *buf, unsigned &buflen)
+{
+ const char *p;
+
+ /* if we can find a CR or NL in the buffer, skip up to it */
+ if ((p = (const char *)memchr(buf, '\r', buflen)) || (p = (const char *)memchr(buf, '\n', buflen))) {
+ /* skip up to it AND one beyond - could be on the NUL symbol now */
+ buflen -= (p - buf) + 1;
+ return p + 1;
+ }
+
+ return nullptr;
+}
+
/****************************************************************************/
NullMixer::NullMixer() :
@@ -142,6 +171,22 @@ NullMixer *
NullMixer::from_text(const char *buf, unsigned &buflen)
{
NullMixer *nm = nullptr;
+ const char *end = buf + buflen;
+
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ return nm;
+ }
+
+ }
if ((buflen >= 2) && (buf[0] == 'Z') && (buf[1] == ':')) {
nm = new NullMixer;
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index bbfa130a9..1c889a811 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -128,7 +128,9 @@
#ifndef _SYSTEMLIB_MIXER_MIXER_H
#define _SYSTEMLIB_MIXER_MIXER_H value
+#include <nuttx/config.h>
#include "drivers/drv_mixer.h"
+#include "mixer_load.h"
/**
* Abstract class defining a mixer mixing zero or more inputs to
@@ -210,6 +212,24 @@ protected:
*/
static int scale_check(struct mixer_scaler_s &scaler);
+ /**
+ * Find a tag
+ *
+ * @param buf The buffer to operate on.
+ * @param buflen length of the buffer.
+ * @param tag character to search for.
+ */
+ static const char * findtag(const char *buf, unsigned &buflen, char tag);
+
+ /**
+ * Skip a line
+ *
+ * @param buf The buffer to operate on.
+ * @param buflen length of the buffer.
+ * @return 0 / OK if a line could be skipped, 1 else
+ */
+ static const char * skipline(const char *buf, unsigned &buflen);
+
private:
};
@@ -239,6 +259,11 @@ public:
void reset();
/**
+ * Count the mixers in the group.
+ */
+ unsigned count();
+
+ /**
* Adds mixers to the group based on a text description in a buffer.
*
* Mixer definitions begin with a single capital letter and a colon.
@@ -424,6 +449,7 @@ public:
HEX_PLUS, /**< hex in + configuration */
OCTA_X,
OCTA_PLUS,
+ OCTA_COX,
MAX_GEOMETRY
};
diff --git a/src/modules/systemlib/mixer/mixer_group.cpp b/src/modules/systemlib/mixer/mixer_group.cpp
index 1dbc512cd..3ed99fba0 100644
--- a/src/modules/systemlib/mixer/mixer_group.cpp
+++ b/src/modules/systemlib/mixer/mixer_group.cpp
@@ -111,6 +111,20 @@ MixerGroup::mix(float *outputs, unsigned space)
return index;
}
+unsigned
+MixerGroup::count()
+{
+ Mixer *mixer = _first;
+ unsigned index = 0;
+
+ while ((mixer != nullptr)) {
+ mixer = mixer->_next;
+ index++;
+ }
+
+ return index;
+}
+
void
MixerGroup::groups_required(uint32_t &groups)
{
@@ -170,6 +184,7 @@ MixerGroup::load_from_buf(const char *buf, unsigned &buflen)
/* only adjust buflen if parsing was successful */
buflen = resid;
+ debug("SUCCESS - buflen: %d", buflen);
} else {
/*
diff --git a/src/modules/mathlib/math/test/test.cpp b/src/modules/systemlib/mixer/mixer_load.c
index 2fa2f7e7c..a55ddf8a3 100644
--- a/src/modules/mathlib/math/test/test.cpp
+++ b/src/modules/systemlib/mixer/mixer_load.c
@@ -32,63 +32,69 @@
****************************************************************************/
/**
- * @file test.cpp
+ * @file mixer_load.c
*
- * Test library code
+ * Programmable multi-channel mixer library.
*/
+#include <nuttx/config.h>
+#include <string.h>
#include <stdio.h>
-#include <math.h>
-#include <stdlib.h>
+#include <ctype.h>
-#include "test.hpp"
+#include "mixer_load.h"
-bool __EXPORT equal(float a, float b, float epsilon)
+int load_mixer_file(const char *fname, char *buf, unsigned maxlen)
{
- float diff = fabsf(a - b);
+ FILE *fp;
+ char line[120];
- if (diff > epsilon) {
- printf("not equal ->\n\ta: %12.8f\n\tb: %12.8f\n", double(a), double(b));
- return false;
-
- } else return true;
-}
-
-void __EXPORT float2SigExp(
- const float &num,
- float &sig,
- int &exp)
-{
- if (isnan(num) || isinf(num)) {
- sig = 0.0f;
- exp = -99;
- return;
- }
-
- if (fabsf(num) < 1.0e-38f) {
- sig = 0;
- exp = 0;
- return;
+ /* open the mixer definition file */
+ fp = fopen(fname, "r");
+ if (fp == NULL) {
+ return 1;
}
- exp = log10f(fabsf(num));
-
- if (exp > 0) {
- exp = ceil(exp);
-
- } else {
- exp = floor(exp);
+ /* read valid lines from the file into a buffer */
+ buf[0] = '\0';
+ for (;;) {
+
+ /* get a line, bail on error/EOF */
+ line[0] = '\0';
+ if (fgets(line, sizeof(line), fp) == NULL)
+ break;
+
+ /* if the line doesn't look like a mixer definition line, skip it */
+ if ((strlen(line) < 2) || !isupper(line[0]) || (line[1] != ':'))
+ continue;
+
+ /* compact whitespace in the buffer */
+ char *t, *f;
+ for (f = line; *f != '\0'; f++) {
+ /* scan for space characters */
+ if (*f == ' ') {
+ /* look for additional spaces */
+ t = f + 1;
+ while (*t == ' ')
+ t++;
+ if (*t == '\0') {
+ /* strip trailing whitespace */
+ *f = '\0';
+ } else if (t > (f + 1)) {
+ memmove(f + 1, t, strlen(t) + 1);
+ }
+ }
+ }
+
+ /* if the line is too long to fit in the buffer, bail */
+ if ((strlen(line) + strlen(buf) + 1) >= maxlen) {
+ return 1;
+ }
+
+ /* add the line to the buffer */
+ strcat(buf, line);
}
- sig = num;
-
- // cheap power since it is integer
- if (exp > 0) {
- for (int i = 0; i < abs(exp); i++) sig /= 10;
-
- } else {
- for (int i = 0; i < abs(exp); i++) sig *= 10;
- }
+ return 0;
}
-
diff --git a/src/modules/mathlib/math/test/test.hpp b/src/modules/systemlib/mixer/mixer_load.h
index 2027bb827..4b7091d5b 100644
--- a/src/modules/mathlib/math/test/test.hpp
+++ b/src/modules/systemlib/mixer/mixer_load.h
@@ -32,19 +32,20 @@
****************************************************************************/
/**
- * @file test.hpp
+ * @file mixer_load.h
*
- * Controller library code
*/
-#pragma once
-//#include <assert.h>
-//#include <time.h>
-//#include <stdlib.h>
+#ifndef _SYSTEMLIB_MIXER_LOAD_H
+#define _SYSTEMLIB_MIXER_LOAD_H value
-bool equal(float a, float b, float eps = 1e-5);
-void float2SigExp(
- const float &num,
- float &sig,
- int &exp);
+#include <nuttx/config.h>
+
+__BEGIN_DECLS
+
+__EXPORT int load_mixer_file(const char *fname, char *buf, unsigned maxlen);
+
+__END_DECLS
+
+#endif
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 8ded0b05c..bf77795d5 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -130,7 +130,17 @@ const MultirotorMixer::Rotor _config_octa_plus[] = {
{ 1.000000, 0.000000, -1.00 },
{ -1.000000, 0.000000, -1.00 },
};
-const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
+const MultirotorMixer::Rotor _config_octa_cox[] = {
+ { -0.707107, 0.707107, 1.00 },
+ { 0.707107, 0.707107, -1.00 },
+ { 0.707107, -0.707107, 1.00 },
+ { -0.707107, -0.707107, -1.00 },
+ { 0.707107, 0.707107, 1.00 },
+ { -0.707107, 0.707107, -1.00 },
+ { -0.707107, -0.707107, 1.00 },
+ { 0.707107, -0.707107, -1.00 },
+};
+const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_quad_x[0],
&_config_quad_plus[0],
&_config_quad_v[0],
@@ -139,8 +149,9 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOME
&_config_hex_plus[0],
&_config_octa_x[0],
&_config_octa_plus[0],
+ &_config_octa_cox[0],
};
-const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
+const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
4, /* quad_x */
4, /* quad_plus */
4, /* quad_v */
@@ -149,6 +160,7 @@ const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
6, /* hex_plus */
8, /* octa_x */
8, /* octa_plus */
+ 8, /* octa_cox */
};
}
@@ -181,6 +193,23 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
char geomname[8];
int s[4];
int used;
+ const char *end = buf + buflen;
+
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ debug("simple parser rejected: No newline / space at end of buf. (#%d/%d: 0x%02x)", i, buflen-1, buf[i]);
+ return nullptr;
+ }
+
+ }
if (sscanf(buf, "R: %s %d %d %d %d%n", geomname, &s[0], &s[1], &s[2], &s[3], &used) != 5) {
debug("multirotor parse failed on '%s'", buf);
@@ -188,11 +217,17 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
}
if (used > (int)buflen) {
- debug("multirotor spec used %d of %u", used, buflen);
+ debug("OVERFLOW: multirotor spec used %d of %u", used, buflen);
+ return nullptr;
+ }
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
return nullptr;
}
- buflen -= used;
+ debug("remaining in buf: %d, first char: %c", buflen, buf[0]);
if (!strcmp(geomname, "4+")) {
geometry = MultirotorMixer::QUAD_PLUS;
@@ -217,6 +252,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
} else if (!strcmp(geomname, "8x")) {
geometry = MultirotorMixer::OCTA_X;
+
+ } else if (!strcmp(geomname, "8c")) {
+ geometry = MultirotorMixer::OCTA_COX;
} else {
debug("unrecognised geometry '%s'", geomname);
diff --git a/src/modules/systemlib/mixer/mixer_simple.cpp b/src/modules/systemlib/mixer/mixer_simple.cpp
index 07dc5f37f..c3985b5de 100644
--- a/src/modules/systemlib/mixer/mixer_simple.cpp
+++ b/src/modules/systemlib/mixer/mixer_simple.cpp
@@ -71,44 +71,30 @@ SimpleMixer::~SimpleMixer()
free(_info);
}
-static const char *
-findtag(const char *buf, unsigned &buflen, char tag)
-{
- while (buflen >= 2) {
- if ((buf[0] == tag) && (buf[1] == ':'))
- return buf;
- buf++;
- buflen--;
- }
- return nullptr;
-}
-
-static void
-skipline(const char *buf, unsigned &buflen)
-{
- const char *p;
-
- /* if we can find a CR or NL in the buffer, skip up to it */
- if ((p = (const char *)memchr(buf, '\r', buflen)) || (p = (const char *)memchr(buf, '\n', buflen)))
- buflen -= (p - buf);
-}
-
int
SimpleMixer::parse_output_scaler(const char *buf, unsigned &buflen, mixer_scaler_s &scaler)
{
int ret;
int s[5];
+ int n = -1;
buf = findtag(buf, buflen, 'O');
- if ((buf == nullptr) || (buflen < 12))
+ if ((buf == nullptr) || (buflen < 12)) {
+ debug("output parser failed finding tag, ret: '%s'", buf);
return -1;
+ }
- if ((ret = sscanf(buf, "O: %d %d %d %d %d",
- &s[0], &s[1], &s[2], &s[3], &s[4])) != 5) {
- debug("scaler parse failed on '%s' (got %d)", buf, ret);
+ if ((ret = sscanf(buf, "O: %d %d %d %d %d %n",
+ &s[0], &s[1], &s[2], &s[3], &s[4], &n)) != 5) {
+ debug("out scaler parse failed on '%s' (got %d, consumed %d)", buf, ret, n);
+ return -1;
+ }
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
return -1;
}
- skipline(buf, buflen);
scaler.negative_scale = s[0] / 10000.0f;
scaler.positive_scale = s[1] / 10000.0f;
@@ -126,15 +112,22 @@ SimpleMixer::parse_control_scaler(const char *buf, unsigned &buflen, mixer_scale
int s[5];
buf = findtag(buf, buflen, 'S');
- if ((buf == nullptr) || (buflen < 16))
+ if ((buf == nullptr) || (buflen < 16)) {
+ debug("control parser failed finding tag, ret: '%s'", buf);
return -1;
+ }
if (sscanf(buf, "S: %u %u %d %d %d %d %d",
&u[0], &u[1], &s[0], &s[1], &s[2], &s[3], &s[4]) != 7) {
debug("control parse failed on '%s'", buf);
return -1;
}
- skipline(buf, buflen);
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ return -1;
+ }
control_group = u[0];
control_index = u[1];
@@ -162,7 +155,11 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
goto out;
}
- buflen -= used;
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ goto out;
+ }
mixinfo = (mixer_simple_s *)malloc(MIXER_SIMPLE_SIZE(inputs));
@@ -173,22 +170,27 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
mixinfo->control_count = inputs;
- if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler))
+ if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler)) {
+ debug("simple mixer parser failed parsing out scaler tag, ret: '%s'", buf);
goto out;
+ }
for (unsigned i = 0; i < inputs; i++) {
if (parse_control_scaler(end - buflen, buflen,
mixinfo->controls[i].scaler,
mixinfo->controls[i].control_group,
- mixinfo->controls[i].control_index))
+ mixinfo->controls[i].control_index)) {
+ debug("simple mixer parser failed parsing ctrl scaler tag, ret: '%s'", buf);
goto out;
+ }
+
}
sm = new SimpleMixer(control_cb, cb_handle, mixinfo);
if (sm != nullptr) {
mixinfo = nullptr;
- debug("loaded mixer with %d inputs", inputs);
+ debug("loaded mixer with %d input(s)", inputs);
} else {
debug("could not allocate memory for mixer");
diff --git a/src/modules/systemlib/mixer/module.mk b/src/modules/systemlib/mixer/module.mk
index 4d45e1c50..fc7485e20 100644
--- a/src/modules/systemlib/mixer/module.mk
+++ b/src/modules/systemlib/mixer/module.mk
@@ -39,4 +39,5 @@ LIBNAME = mixerlib
SRCS = mixer.cpp \
mixer_group.cpp \
mixer_multirotor.cpp \
- mixer_simple.cpp
+ mixer_simple.cpp \
+ mixer_load.c
diff --git a/src/modules/systemlib/mixer/multi_tables b/src/modules/systemlib/mixer/multi_tables
index 683c63040..050bf2f47 100755
--- a/src/modules/systemlib/mixer/multi_tables
+++ b/src/modules/systemlib/mixer/multi_tables
@@ -74,7 +74,18 @@ set octa_plus {
90 CW
}
-set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus}
+set octa_cox {
+ 45 CCW
+ -45 CW
+ -135 CCW
+ 135 CW
+ -45 CCW
+ 45 CW
+ 135 CCW
+ -135 CW
+}
+
+set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus octa_cox}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index fd0289c9a..3953b757d 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -45,6 +45,12 @@ SRCS = err.c \
getopt_long.c \
up_cxxinitialize.c \
pid/pid.c \
- geo/geo.c \
systemlib.c \
- airspeed.c
+ airspeed.c \
+ system_params.c \
+ mavlink_log.c \
+ rc_check.c \
+ otp.c \
+ board_serial.c \
+ pwm_limit/pwm_limit.c
+
diff --git a/src/modules/systemlib/otp.c b/src/modules/systemlib/otp.c
new file mode 100644
index 000000000..695574fdc
--- /dev/null
+++ b/src/modules/systemlib/otp.c
@@ -0,0 +1,224 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ * Authors:
+ * Lorenz Meier <lm@inf.ethz.ch>
+ * David "Buzz" Bussenschutt <davidbuzz@gmail.com>
+ *
+ * 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 otp.c
+ * otp estimation
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author David "Buzz" Bussenschutt <davidbuzz@gmail.com>
+ *
+ */
+
+#include <nuttx/config.h>
+#include <board_config.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+#include <string.h> // memset
+#include "conversions.h"
+#include "otp.h"
+#include "err.h" // warnx
+#include <assert.h>
+
+
+int val_read(void *dest, volatile const void *src, int bytes)
+{
+
+ int i;
+
+ for (i = 0; i < bytes / 4; i++) {
+ *(((volatile unsigned *)dest) + i) = *(((volatile unsigned *)src) + i);
+ }
+
+ return i * 4;
+}
+
+
+int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature)
+{
+
+ warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n", id_type, vid, pid);
+
+ int errors = 0;
+
+ // descriptor
+ if (F_write_byte(ADDR_OTP_START, 'P'))
+ errors++;
+ // write the 'P' from PX4. to first byte in OTP
+ if (F_write_byte(ADDR_OTP_START + 1, 'X'))
+ errors++; // write the 'P' from PX4. to first byte in OTP
+ if (F_write_byte(ADDR_OTP_START + 2, '4'))
+ errors++;
+ if (F_write_byte(ADDR_OTP_START + 3, '\0'))
+ errors++;
+ //id_type
+ if (F_write_byte(ADDR_OTP_START + 4, id_type))
+ errors++;
+ // vid and pid are 4 bytes each
+ if (F_write_word(ADDR_OTP_START + 5, vid))
+ errors++;
+ if (F_write_word(ADDR_OTP_START + 9, pid))
+ errors++;
+
+ // leave some 19 bytes of space, and go to the next block...
+ // then the auth sig starts
+ for (int i = 0 ; i < 128 ; i++) {
+ if (F_write_byte(ADDR_OTP_START + 32 + i, signature[i]))
+ errors++;
+ }
+
+ return errors;
+}
+
+int lock_otp(void)
+{
+ //determine the required locking size - can only write full lock bytes */
+// int size = sizeof(struct otp) / 32;
+//
+// struct otp_lock otp_lock_mem;
+//
+// memset(&otp_lock_mem, OTP_LOCK_UNLOCKED, sizeof(otp_lock_mem));
+// for (int i = 0; i < sizeof(otp_lock_mem) / sizeof(otp_lock_mem.lock_bytes[0]); i++)
+// otp_lock_mem.lock_bytes[i] = OTP_LOCK_LOCKED;
+ //XXX add the actual call here to write the OTP_LOCK bytes only at final stage
+ // val_copy(lock_ptr, &otp_lock_mem, sizeof(otp_lock_mem));
+
+ int locksize = 5;
+
+ int errors = 0;
+
+ // or just realise it's exctly 5x 32byte blocks we need to lock. 1 block for ID,type,vid,pid, and 4 blocks for certificate, which is 128 bytes.
+ for (int i = 0 ; i < locksize ; i++) {
+ if (F_write_byte(ADDR_OTP_LOCK_START + i, OTP_LOCK_LOCKED))
+ errors++;
+ }
+
+ return errors;
+}
+
+
+
+// COMPLETE, BUSY, or other flash error?
+int F_GetStatus(void)
+{
+ int fs = F_COMPLETE;
+
+ if ((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else {
+
+ if ((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else {
+
+ if ((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else {
+
+ if ((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else {
+ fs = F_COMPLETE;
+ }
+ }
+ }
+ }
+
+ return fs;
+}
+
+
+// enable FLASH Registers
+void F_unlock(void)
+{
+ if ((FLASH->control & F_CR_LOCK) != 0) {
+ FLASH->key = F_KEY1;
+ FLASH->key = F_KEY2;
+ }
+}
+
+// lock the FLASH Registers
+void F_lock(void)
+{
+ FLASH->control |= F_CR_LOCK;
+}
+
+// flash write word.
+int F_write_word(uint32_t Address, uint32_t Data)
+{
+ unsigned char octet[4] = {0, 0, 0, 0};
+
+ int ret = 0;
+
+ for (int i = 0; i < 4; i++) {
+ octet[i] = (Data >> (i * 8)) & 0xFF;
+ ret = F_write_byte(Address + i, octet[i]);
+ }
+
+ return ret;
+}
+
+// flash write byte
+int F_write_byte(uint32_t Address, uint8_t Data)
+{
+ volatile int status = F_COMPLETE;
+
+ //warnx("F_write_byte: %08X %02d", Address , Data ) ;
+
+ //Check the parameters
+ assert(IS_F_ADDRESS(Address));
+
+ //Wait for FLASH operation to complete by polling on BUSY flag.
+ status = F_GetStatus();
+
+ while (status == F_BUSY) { status = F_GetStatus();}
+
+ if (status == F_COMPLETE) {
+ //if the previous operation is completed, proceed to program the new data
+ FLASH->control &= CR_PSIZE_MASK;
+ FLASH->control |= F_PSIZE_BYTE;
+ FLASH->control |= F_CR_PG;
+
+ *(volatile uint8_t *)Address = Data;
+
+ //Wait for FLASH operation to complete by polling on BUSY flag.
+ status = F_GetStatus();
+
+ while (status == F_BUSY) { status = F_GetStatus();}
+
+ //if the program operation is completed, disable the PG Bit
+ FLASH->control &= (~F_CR_PG);
+ }
+
+ //Return the Program Status
+ return !(status == F_COMPLETE);
+}
+
+
+
diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h
new file mode 100644
index 000000000..f10e129d8
--- /dev/null
+++ b/src/modules/systemlib/otp.h
@@ -0,0 +1,151 @@
+/****************************************************************************
+ *
+ * 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 otp.h
+ * One TIme Programmable ( OTP ) Flash routine/s.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author David "Buzz" Bussenschutt <davidbuzz@gmail.com>
+ *
+ */
+
+#ifndef OTP_H_
+#define OTP_H_
+
+__BEGIN_DECLS
+
+#define ADDR_OTP_START 0x1FFF7800
+#define ADDR_OTP_LOCK_START 0x1FFF7A00
+
+#define OTP_LOCK_LOCKED 0x00
+#define OTP_LOCK_UNLOCKED 0xFF
+
+
+
+#include <unistd.h>
+#include <stdio.h>
+
+// possible flash statuses
+#define F_BUSY 1
+#define F_ERROR_WRP 2
+#define F_ERROR_PROGRAM 3
+#define F_ERROR_OPERATION 4
+#define F_COMPLETE 5
+
+typedef struct {
+ volatile uint32_t accesscontrol; // 0x00
+ volatile uint32_t key; // 0x04
+ volatile uint32_t optionkey; // 0x08
+ volatile uint32_t status; // 0x0C
+ volatile uint32_t control; // 0x10
+ volatile uint32_t optioncontrol; //0x14
+} flash_registers;
+
+#define PERIPH_BASE ((uint32_t)0x40000000) //Peripheral base address
+#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000)
+#define F_R_BASE (AHB1PERIPH_BASE + 0x3C00)
+#define FLASH ((flash_registers *) F_R_BASE)
+
+#define F_BSY ((uint32_t)0x00010000) //FLASH Busy flag bit
+#define F_OPERR ((uint32_t)0x00000002) //FLASH operation Error flag bit
+#define F_WRPERR ((uint32_t)0x00000010) //FLASH Write protected error flag bit
+#define CR_PSIZE_MASK ((uint32_t)0xFFFFFCFF)
+#define F_PSIZE_WORD ((uint32_t)0x00000200)
+#define F_PSIZE_BYTE ((uint32_t)0x00000000)
+#define F_CR_PG ((uint32_t)0x00000001) // a bit in the F_CR register
+#define F_CR_LOCK ((uint32_t)0x80000000) // also another bit.
+
+#define F_KEY1 ((uint32_t)0x45670123)
+#define F_KEY2 ((uint32_t)0xCDEF89AB)
+#define IS_F_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) || (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F)))
+
+
+
+#pragma pack(push, 1)
+
+/*
+ * The OTP area is divided into 16 OTP data blocks of 32 bytes and one lock OTP block of 16 bytes.
+ * The OTP data and lock blocks cannot be erased. The lock block contains 16 bytes LOCKBi (0 ≤ i ≤ 15)
+ * to lock the corresponding OTP data block (blocks 0 to 15). Each OTP data block can be programmed
+ * until the value 0x00 is programmed in the corresponding OTP lock byte. The lock bytes must only
+ * contain 0x00 and 0xFF values, otherwise the OTP bytes might not be taken into account correctly.
+ */
+
+struct otp {
+ // first 32 bytes = the '0' Block
+ char id[4]; ///4 bytes < 'P' 'X' '4' '\n'
+ uint8_t id_type; ///1 byte < 0 for USB VID, 1 for generic VID
+ uint32_t vid; ///4 bytes
+ uint32_t pid; ///4 bytes
+ char unused[19]; ///19 bytes
+ // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block )
+ char signature[128];
+ // insert extras here
+ uint32_t lock_bytes[4];
+};
+
+struct otp_lock {
+ uint8_t lock_bytes[16];
+};
+#pragma pack(pop)
+
+#define ADDR_F_SIZE 0x1FFF7A22
+
+#pragma pack(push, 1)
+union udid {
+ uint32_t serial[3];
+ char data[12];
+};
+#pragma pack(pop)
+
+
+/**
+ * s
+ */
+//__EXPORT float calc_indicated_airspeed(float differential_pressure);
+
+__EXPORT void F_unlock(void);
+__EXPORT void F_lock(void);
+__EXPORT int val_read(void *dest, volatile const void *src, int bytes);
+__EXPORT int val_write(volatile void *dest, const void *src, int bytes);
+__EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature);
+__EXPORT int lock_otp(void);
+
+
+__EXPORT int F_write_byte(uint32_t Address, uint8_t Data);
+__EXPORT int F_write_word(uint32_t Address, uint32_t Data);
+
+__END_DECLS
+
+#endif
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index 69a9bdf9b..2d773fd25 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -48,6 +48,7 @@
#include <unistd.h>
#include <systemlib/err.h>
#include <errno.h>
+#include <semaphore.h>
#include <sys/stat.h>
@@ -60,7 +61,7 @@
#include "uORB/uORB.h"
#include "uORB/topics/parameter_update.h"
-#if 1
+#if 0
# define debug(fmt, args...) do { warnx(fmt, ##args); } while(0)
#else
# define debug(fmt, args...) do { } while(0)
@@ -95,18 +96,20 @@ ORB_DEFINE(parameter_update, struct parameter_update_s);
/** parameter update topic handle */
static orb_advert_t param_topic = -1;
+static sem_t param_sem = { .semcount = 1 };
+
/** lock the parameter store */
static void
param_lock(void)
{
- /* XXX */
+ //do {} while (sem_wait(&param_sem) != 0);
}
/** unlock the parameter store */
static void
param_unlock(void)
{
- /* XXX */
+ //sem_post(&param_sem);
}
/** assert that the parameter store is locked */
@@ -505,27 +508,86 @@ param_get_default_file(void)
int
param_save_default(void)
{
- /* delete the file in case it exists */
- unlink(param_get_default_file());
+ int res;
+ int fd;
- /* create the file */
- int fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL);
+ const char *filename = param_get_default_file();
+
+ /* write parameters to temp file */
+ fd = open(filename, O_WRONLY | O_CREAT);
if (fd < 0) {
- warn("opening '%s' for writing failed", param_get_default_file());
- return -1;
+ warn("failed to open param file: %s", filename);
+ return ERROR;
+ }
+
+ if (res == OK) {
+ res = param_export(fd, false);
+
+ if (res != OK) {
+ warnx("failed to write parameters to file: %s", filename);
+ }
}
- int result = param_export(fd, false);
close(fd);
- if (result != 0) {
- warn("error exporting parameters to '%s'", param_get_default_file());
- unlink(param_get_default_file());
- return -2;
+ return res;
+
+#if 0
+ const char *filename_tmp = malloc(strlen(filename) + 5);
+ sprintf(filename_tmp, "%s.tmp", filename);
+
+ /* delete temp file if exist */
+ res = unlink(filename_tmp);
+
+ if (res != OK && errno == ENOENT)
+ res = OK;
+
+ if (res != OK)
+ warn("failed to delete temp file: %s", filename_tmp);
+
+ if (res == OK) {
+ /* write parameters to temp file */
+ fd = open(filename_tmp, O_WRONLY | O_CREAT | O_EXCL);
+
+ if (fd < 0) {
+ warn("failed to open temp file: %s", filename_tmp);
+ res = ERROR;
+ }
+
+ if (res == OK) {
+ res = param_export(fd, false);
+
+ if (res != OK)
+ warnx("failed to write parameters to file: %s", filename_tmp);
+ }
+
+ close(fd);
}
- return 0;
+ if (res == OK) {
+ /* delete parameters file */
+ res = unlink(filename);
+
+ if (res != OK && errno == ENOENT)
+ res = OK;
+
+ if (res != OK)
+ warn("failed to delete parameters file: %s", filename);
+ }
+
+ if (res == OK) {
+ /* rename temp file to parameters */
+ res = rename(filename_tmp, filename);
+
+ if (res != OK)
+ warn("failed to rename %s to %s", filename_tmp, filename);
+ }
+
+ free(filename_tmp);
+
+ return res;
+#endif
}
/**
@@ -534,9 +596,9 @@ param_save_default(void)
int
param_load_default(void)
{
- int fd = open(param_get_default_file(), O_RDONLY);
+ int fd_load = open(param_get_default_file(), O_RDONLY);
- if (fd < 0) {
+ if (fd_load < 0) {
/* no parameter file is OK, otherwise this is an error */
if (errno != ENOENT) {
warn("open '%s' for reading failed", param_get_default_file());
@@ -545,8 +607,8 @@ param_load_default(void)
return 1;
}
- int result = param_load(fd);
- close(fd);
+ int result = param_load(fd_load);
+ close(fd_load);
if (result != 0) {
warn("error reading parameters from '%s'", param_get_default_file());
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index 879f4715a..b4ca0ed3e 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -201,17 +201,23 @@ perf_end(perf_counter_t handle)
switch (handle->type) {
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
- hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
- pce->event_count++;
- pce->time_total += elapsed;
+ if (pce->time_start != 0) {
+ hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
- if ((pce->time_least > elapsed) || (pce->time_least == 0))
- pce->time_least = elapsed;
+ pce->event_count++;
+ pce->time_total += elapsed;
- if (pce->time_most < elapsed)
- pce->time_most = elapsed;
+ if ((pce->time_least > elapsed) || (pce->time_least == 0))
+ pce->time_least = elapsed;
+
+ if (pce->time_most < elapsed)
+ pce->time_most = elapsed;
+
+ pce->time_start = 0;
+ }
}
+ break;
default:
break;
@@ -219,6 +225,27 @@ perf_end(perf_counter_t handle)
}
void
+perf_cancel(perf_counter_t handle)
+{
+ if (handle == NULL)
+ return;
+
+ switch (handle->type) {
+ case PC_ELAPSED: {
+ struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
+
+ pce->time_start = 0;
+ }
+ break;
+
+ default:
+ break;
+ }
+}
+
+
+
+void
perf_reset(perf_counter_t handle)
{
if (handle == NULL)
@@ -268,10 +295,11 @@ perf_print_counter(perf_counter_t handle)
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
- printf("%s: %llu events, %lluus elapsed, min %lluus max %lluus\n",
+ printf("%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
handle->name,
pce->event_count,
pce->time_total,
+ pce->time_total / pce->event_count,
pce->time_least,
pce->time_most);
break;
@@ -294,6 +322,32 @@ perf_print_counter(perf_counter_t handle)
}
}
+uint64_t
+perf_event_count(perf_counter_t handle)
+{
+ if (handle == NULL)
+ return 0;
+
+ switch (handle->type) {
+ case PC_COUNT:
+ return ((struct perf_ctr_count *)handle)->event_count;
+
+ case PC_ELAPSED: {
+ struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
+ return pce->event_count;
+ }
+
+ case PC_INTERVAL: {
+ struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
+ return pci->event_count;
+ }
+
+ default:
+ break;
+ }
+ return 0;
+}
+
void
perf_print_all(void)
{
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index 5c2cb15b2..e1e3cbe95 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -92,13 +92,25 @@ __EXPORT extern void perf_begin(perf_counter_t handle);
* End a performance event.
*
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
+ * If a call is made without a corresopnding perf_begin call, or if perf_cancel
+ * has been called subsequently, no change is made to the counter.
*
* @param handle The handle returned from perf_alloc.
*/
__EXPORT extern void perf_end(perf_counter_t handle);
/**
- * Reset a performance event.
+ * Cancel a performance event.
+ *
+ * This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
+ * It reverts the effect of a previous perf_begin.
+ *
+ * @param handle The handle returned from perf_alloc.
+ */
+__EXPORT extern void perf_cancel(perf_counter_t handle);
+
+/**
+ * Reset a performance counter.
*
* This call resets performance counter to initial state
*
@@ -123,6 +135,14 @@ __EXPORT extern void perf_print_all(void);
*/
__EXPORT extern void perf_reset_all(void);
+/**
+ * Return current event_count
+ *
+ * @param handle The counter returned from perf_alloc.
+ * @return event_count
+ */
+__EXPORT extern uint64_t perf_event_count(perf_counter_t handle);
+
__END_DECLS
#endif
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 49315cdc9..77c952f52 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -1,9 +1,11 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Laurens Mackay <mackayl@student.ethz.ch>
+ * Tobias Naegeli <naegelit@student.ethz.ch>
+ * Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ * Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,14 +38,23 @@
/**
* @file pid.c
- * Implementation of generic PID control interface
+ *
+ * Implementation of generic PID control interface.
+ *
+ * @author Laurens Mackay <mackayl@student.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#include "pid.h"
#include <math.h>
+#define SIGMA 0.000001f
+
__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax,
- float limit, uint8_t mode)
+ float limit, uint8_t mode, float dt_min)
{
pid->kp = kp;
pid->ki = ki;
@@ -51,13 +62,13 @@ __EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax,
pid->intmax = intmax;
pid->limit = limit;
pid->mode = mode;
- pid->count = 0;
- pid->saturated = 0;
- pid->last_output = 0;
-
- pid->sp = 0;
- pid->error_previous = 0;
- pid->integral = 0;
+ pid->dt_min = dt_min;
+ pid->count = 0.0f;
+ pid->saturated = 0.0f;
+ pid->last_output = 0.0f;
+ pid->sp = 0.0f;
+ pid->error_previous = 0.0f;
+ pid->integral = 0.0f;
}
__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax, float limit)
{
@@ -136,14 +147,14 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
// Calculated current error value
float error = pid->sp - val;
- if (isfinite(error)) { // Why is this necessary? DEW
- pid->error_previous = error;
- }
-
// Calculate or measured current error derivative
-
if (pid->mode == PID_MODE_DERIVATIV_CALC) {
- d = (error - pid->error_previous) / dt;
+ d = (error - pid->error_previous) / fmaxf(dt, pid->dt_min);
+ pid->error_previous = error;
+
+ } else if (pid->mode == PID_MODE_DERIVATIV_CALC_NO_SP) {
+ d = (-val - pid->error_previous) / fmaxf(dt, pid->dt_min);
+ pid->error_previous = -val;
} else if (pid->mode == PID_MODE_DERIVATIV_SET) {
d = -val_dot;
@@ -152,35 +163,49 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
d = 0.0f;
}
- // Calculate the error integral and check for saturation
- i = pid->integral + (error * dt);
+ if (!isfinite(d)) {
+ d = 0.0f;
+ }
- if (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit ||
- fabsf(i) > pid->intmax) {
- i = pid->integral; // If saturated then do not update integral value
- pid->saturated = 1;
+ if (pid->ki > 0.0f) {
+ // Calculate the error integral and check for saturation
+ i = pid->integral + (error * dt);
- } else {
- if (!isfinite(i)) {
- i = 0;
+ if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) ||
+ fabsf(i) > pid->intmax) {
+ i = pid->integral; // If saturated then do not update integral value
+ pid->saturated = 1;
+
+ } else {
+ if (!isfinite(i)) {
+ i = 0.0f;
+ }
+
+ pid->integral = i;
+ pid->saturated = 0;
}
- pid->integral = i;
+ } else {
+ i = 0.0f;
pid->saturated = 0;
}
// Calculate the output. Limit output magnitude to pid->limit
- float output = (pid->error_previous * pid->kp) + (i * pid->ki) + (d * pid->kd);
+ float output = (error * pid->kp) + (i * pid->ki) + (d * pid->kd);
- if (output > pid->limit) output = pid->limit;
+ if (isfinite(output)) {
+ if (pid->limit > SIGMA) {
+ if (output > pid->limit) {
+ output = pid->limit;
- if (output < -pid->limit) output = -pid->limit;
+ } else if (output < -pid->limit) {
+ output = -pid->limit;
+ }
+ }
- if (isfinite(output)) {
pid->last_output = output;
}
-
return pid->last_output;
}
diff --git a/src/modules/systemlib/pid/pid.h b/src/modules/systemlib/pid/pid.h
index 64d668867..eca228464 100644
--- a/src/modules/systemlib/pid/pid.h
+++ b/src/modules/systemlib/pid/pid.h
@@ -1,9 +1,11 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Laurens Mackay <mackayl@student.ethz.ch>
+ * Tobias Naegeli <naegelit@student.ethz.ch>
+ * Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ * Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,7 +38,14 @@
/**
* @file pid.h
- * Definition of generic PID control interface
+ *
+ * Definition of generic PID control interface.
+ *
+ * @author Laurens Mackay <mackayl@student.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef PID_H_
@@ -44,11 +53,16 @@
#include <stdint.h>
+__BEGIN_DECLS
+
/* PID_MODE_DERIVATIV_CALC calculates discrete derivative from previous error
* val_dot in pid_calculate() will be ignored */
#define PID_MODE_DERIVATIV_CALC 0
+/* PID_MODE_DERIVATIV_CALC_NO_SP calculates discrete derivative from previous value, setpoint derivative is ignored
+ * val_dot in pid_calculate() will be ignored */
+#define PID_MODE_DERIVATIV_CALC_NO_SP 1
/* Use PID_MODE_DERIVATIV_SET if you have the derivative already (Gyros, Kalman) */
-#define PID_MODE_DERIVATIV_SET 1
+#define PID_MODE_DERIVATIV_SET 2
// Use PID_MODE_DERIVATIV_NONE for a PI controller (vs PID)
#define PID_MODE_DERIVATIV_NONE 9
@@ -62,17 +76,19 @@ typedef struct {
float error_previous;
float last_output;
float limit;
+ float dt_min;
uint8_t mode;
uint8_t count;
uint8_t saturated;
} PID_t;
-__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax, float limit, uint8_t mode);
+__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax, float limit, uint8_t mode, float dt_min);
__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax, float limit);
//void pid_set(PID_t *pid, float sp);
__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt);
__EXPORT void pid_reset_integral(PID_t *pid);
+__END_DECLS
#endif /* PID_H_ */
diff --git a/src/modules/systemlib/ppm_decode.h b/src/modules/systemlib/ppm_decode.h
index 6c5e15345..5a1ad84da 100644
--- a/src/modules/systemlib/ppm_decode.h
+++ b/src/modules/systemlib/ppm_decode.h
@@ -57,6 +57,7 @@ __BEGIN_DECLS
* PPM decoder state
*/
__EXPORT extern uint16_t ppm_buffer[PPM_MAX_CHANNELS]; /**< decoded PPM channel values */
+__EXPORT extern uint16_t ppm_frame_length; /**< length of the decoded PPM frame (includes gap) */
__EXPORT extern unsigned ppm_decoded_channels; /**< count of decoded channels */
__EXPORT extern hrt_abstime ppm_last_valid_decode; /**< timestamp of the last valid decode */
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
new file mode 100644
index 000000000..190b315f1
--- /dev/null
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -0,0 +1,151 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ * Author: Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 pwm_limit.c
+ *
+ * Lib to limit PWM output
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#include "pwm_limit.h"
+#include <math.h>
+#include <stdbool.h>
+#include <drivers/drv_hrt.h>
+#include <stdio.h>
+
+void pwm_limit_init(pwm_limit_t *limit)
+{
+ limit->state = PWM_LIMIT_STATE_INIT;
+ limit->time_armed = 0;
+ return;
+}
+
+void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
+{
+
+ /* first evaluate state changes */
+ switch (limit->state) {
+ case PWM_LIMIT_STATE_INIT:
+
+ if (armed) {
+
+ /* set arming time for the first call */
+ if (limit->time_armed == 0) {
+ limit->time_armed = hrt_absolute_time();
+ }
+
+ if (hrt_elapsed_time(&limit->time_armed) >= INIT_TIME_US) {
+ limit->state = PWM_LIMIT_STATE_OFF;
+ }
+ }
+ break;
+ case PWM_LIMIT_STATE_OFF:
+ if (armed) {
+ limit->state = PWM_LIMIT_STATE_RAMP;
+
+ /* reset arming time, used for ramp timing */
+ limit->time_armed = hrt_absolute_time();
+ }
+ break;
+ case PWM_LIMIT_STATE_RAMP:
+ if (!armed) {
+ limit->state = PWM_LIMIT_STATE_OFF;
+ } else if (hrt_elapsed_time(&limit->time_armed) >= RAMP_TIME_US) {
+ limit->state = PWM_LIMIT_STATE_ON;
+ }
+ break;
+ case PWM_LIMIT_STATE_ON:
+ if (!armed) {
+ limit->state = PWM_LIMIT_STATE_OFF;
+ }
+ break;
+ default:
+ break;
+ }
+
+ unsigned progress;
+ uint16_t temp_pwm;
+
+ /* then set effective_pwm based on state */
+ switch (limit->state) {
+ case PWM_LIMIT_STATE_OFF:
+ case PWM_LIMIT_STATE_INIT:
+ for (unsigned i=0; i<num_channels; i++) {
+ effective_pwm[i] = disarmed_pwm[i];
+ }
+ break;
+ case PWM_LIMIT_STATE_RAMP:
+ {
+ hrt_abstime diff = hrt_elapsed_time(&limit->time_armed);
+
+ progress = diff * 10000 / RAMP_TIME_US;
+
+ for (unsigned i=0; i<num_channels; i++) {
+
+ uint16_t ramp_min_pwm;
+
+ /* if a disarmed pwm value was set, blend between disarmed and min */
+ if (disarmed_pwm[i] > 0) {
+
+ /* safeguard against overflows */
+ unsigned disarmed = disarmed_pwm[i];
+ if (disarmed > min_pwm[i]) {
+ disarmed = min_pwm[i];
+ }
+
+ unsigned disarmed_min_diff = min_pwm[i] - disarmed;
+ ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / 10000;
+
+ } else {
+
+ /* no disarmed pwm value set, choose min pwm */
+ ramp_min_pwm = min_pwm[i];
+ }
+
+ effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
+ }
+ }
+ break;
+ case PWM_LIMIT_STATE_ON:
+ for (unsigned i=0; i<num_channels; i++) {
+ effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
+ }
+ break;
+ default:
+ break;
+ }
+ return;
+}
diff --git a/src/modules/mathlib/math/Dcm.hpp b/src/modules/systemlib/pwm_limit/pwm_limit.h
index 28d840b10..6a667ac6f 100644
--- a/src/modules/mathlib/math/Dcm.hpp
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.h
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,72 +33,47 @@
****************************************************************************/
/**
- * @file Dcm.hpp
+ * @file pwm_limit.h
*
- * math direction cosine matrix
+ * Lib to limit PWM output
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
*/
-//#pragma once
-
-#include "Vector.hpp"
-#include "Matrix.hpp"
+#ifndef PWM_LIMIT_H_
+#define PWM_LIMIT_H_
-namespace math
-{
+#include <stdint.h>
+#include <stdbool.h>
-class Quaternion;
-class EulerAngles;
+__BEGIN_DECLS
-/**
- * This is a Tait Bryan, Body 3-2-1 sequence.
- * (yaw)-(pitch)-(roll)
- * The Dcm transforms a vector in the body frame
- * to the navigation frame, typically represented
- * as C_nb. C_bn can be obtained through use
- * of the transpose() method.
+/*
+ * time for the ESCs to initialize
+ * (this is not actually needed if PWM is sent right after boot)
*/
-class __EXPORT Dcm : public Matrix
-{
-public:
- /**
- * default ctor
- */
- Dcm();
-
- /**
- * scalar ctor
- */
- Dcm(float c00, float c01, float c02,
- float c10, float c11, float c12,
- float c20, float c21, float c22);
-
- /**
- * data ctor
- */
- Dcm(const float *data);
-
- /**
- * quaternion ctor
- */
- Dcm(const Quaternion &q);
+#define INIT_TIME_US 500000
+/*
+ * time to slowly ramp up the ESCs
+ */
+#define RAMP_TIME_US 2500000
- /**
- * euler angles ctor
- */
- Dcm(const EulerAngles &euler);
+enum pwm_limit_state {
+ PWM_LIMIT_STATE_OFF = 0,
+ PWM_LIMIT_STATE_INIT,
+ PWM_LIMIT_STATE_RAMP,
+ PWM_LIMIT_STATE_ON
+};
- /**
- * copy ctor (deep)
- */
- Dcm(const Dcm &right);
+typedef struct {
+ enum pwm_limit_state state;
+ uint64_t time_armed;
+} pwm_limit_t;
- /**
- * dtor
- */
- virtual ~Dcm();
-};
+__EXPORT void pwm_limit_init(pwm_limit_t *limit);
-int __EXPORT dcmTest();
+__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
-} // math
+__END_DECLS
+#endif /* PWM_LIMIT_H_ */
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
new file mode 100644
index 000000000..21e15ec56
--- /dev/null
+++ b/src/modules/systemlib/rc_check.c
@@ -0,0 +1,151 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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 rc_check.c
+ *
+ * RC calibration check
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <fcntl.h>
+
+#include <systemlib/rc_check.h>
+#include <systemlib/param/param.h>
+#include <mavlink/mavlink_log.h>
+#include <drivers/drv_rc_input.h>
+
+int rc_calibration_check(int mavlink_fd) {
+
+ char nbuf[20];
+ param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
+ _parameter_handles_rev, _parameter_handles_dz;
+
+ float param_min, param_max, param_trim, param_rev, param_dz;
+
+ /* first check channel mappings */
+ /* check which map param applies */
+ // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
+ // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
+ // /* give system time to flush error message in case there are more */
+ // usleep(100000);
+ // count++;
+ // }
+
+ int channel_fail_count = 0;
+
+ for (int i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
+ /* should the channel be enabled? */
+ uint8_t count = 0;
+
+ /* min values */
+ sprintf(nbuf, "RC%d_MIN", i + 1);
+ _parameter_handles_min = param_find(nbuf);
+ param_get(_parameter_handles_min, &param_min);
+
+ /* trim values */
+ sprintf(nbuf, "RC%d_TRIM", i + 1);
+ _parameter_handles_trim = param_find(nbuf);
+ param_get(_parameter_handles_trim, &param_trim);
+
+ /* max values */
+ sprintf(nbuf, "RC%d_MAX", i + 1);
+ _parameter_handles_max = param_find(nbuf);
+ param_get(_parameter_handles_max, &param_max);
+
+ /* channel reverse */
+ sprintf(nbuf, "RC%d_REV", i + 1);
+ _parameter_handles_rev = param_find(nbuf);
+ param_get(_parameter_handles_rev, &param_rev);
+
+ /* channel deadzone */
+ sprintf(nbuf, "RC%d_DZ", i + 1);
+ _parameter_handles_dz = param_find(nbuf);
+ param_get(_parameter_handles_dz, &param_dz);
+
+ /* assert min..center..max ordering */
+ if (param_min < 500) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_max > 2500) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_trim < param_min) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN (%d/%d)", i+1, (int)param_trim, (int)param_min);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_trim > param_max) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX (%d/%d)", i+1, (int)param_trim, (int)param_max);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+
+ /* assert deadzone is sane */
+ if (param_dz > 500) {
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ count++;
+ }
+
+ /* check which map param applies */
+ // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
+ // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
+ // /* give system time to flush error message in case there are more */
+ // usleep(100000);
+ // count++;
+ // }
+
+ /* sanity checks pass, enable channel */
+ if (count) {
+ mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ warnx(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ usleep(100000);
+ }
+
+ channel_fail_count += count;
+ }
+
+ return channel_fail_count;
+}
diff --git a/src/modules/systemlib/rc_check.h b/src/modules/systemlib/rc_check.h
new file mode 100644
index 000000000..e70b83cce
--- /dev/null
+++ b/src/modules/systemlib/rc_check.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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 rc_check.h
+ *
+ * RC calibration check
+ */
+
+#pragma once
+
+ __BEGIN_DECLS
+
+/**
+ * Check the RC calibration
+ *
+ * @return 0 / OK if RC calibration is ok, index + 1 of the first
+ * channel that failed else (so 1 == first channel failed)
+ */
+__EXPORT int rc_calibration_check(int mavlink_fd);
+
+__END_DECLS
diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c
new file mode 100644
index 000000000..75be090f8
--- /dev/null
+++ b/src/modules/systemlib/system_params.c
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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 system_params.c
+ *
+ * System wide parameters
+ */
+
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
+
+// Auto-start script with index #n
+PARAM_DEFINE_INT32(SYS_AUTOSTART, 0);
+
+// Automatically configure default values
+PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0);
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 3283aad8a..57a751e1c 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -43,13 +43,29 @@
#include <fcntl.h>
#include <sched.h>
#include <signal.h>
-#include <sys/stat.h>
#include <unistd.h>
#include <float.h>
#include <string.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+
+#include <stm32_pwr.h>
+
#include "systemlib.h"
+void
+systemreset(bool to_bootloader)
+{
+ if (to_bootloader) {
+ stm32_pwr_enablebkp();
+
+ /* XXX wow, this is evil - write a magic number into backup register zero */
+ *(uint32_t *)0x40002850 = 0xb007b007;
+ }
+ up_systemreset();
+}
+
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
void killall()
diff --git a/src/modules/systemlib/systemlib.h b/src/modules/systemlib/systemlib.h
index 0194b5e52..3728f2067 100644
--- a/src/modules/systemlib/systemlib.h
+++ b/src/modules/systemlib/systemlib.h
@@ -42,11 +42,11 @@
#include <float.h>
#include <stdint.h>
-/** Reboots the board */
-extern void up_systemreset(void) noreturn_function;
-
__BEGIN_DECLS
+/** Reboots the board */
+__EXPORT void systemreset(bool to_bootloader) noreturn_function;
+
/** Sends SIGUSR1 to all processes */
__EXPORT void killall(void);
diff --git a/src/modules/test/foo.c b/src/modules/test/foo.c
deleted file mode 100644
index ff6af031f..000000000
--- a/src/modules/test/foo.c
+++ /dev/null
@@ -1,4 +0,0 @@
-int test_main(void)
-{
- return 0;
-} \ No newline at end of file
diff --git a/src/modules/test/module.mk b/src/modules/test/module.mk
deleted file mode 100644
index abf80eedf..000000000
--- a/src/modules/test/module.mk
+++ /dev/null
@@ -1,4 +0,0 @@
-
-MODULE_NAME = test
-SRCS = foo.c
-
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 4197f6fb2..c6a252b55 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -37,6 +37,10 @@
* Common object definitions without a better home.
*/
+/**
+ * @defgroup topics List of all uORB topics.
+ */
+
#include <nuttx/config.h>
#include <drivers/drv_orb_dev.h>
@@ -77,9 +81,15 @@ ORB_DEFINE(home_position, struct home_position_s);
#include "topics/vehicle_status.h"
ORB_DEFINE(vehicle_status, struct vehicle_status_s);
+#include "topics/safety.h"
+ORB_DEFINE(safety, struct safety_s);
+
#include "topics/battery_status.h"
ORB_DEFINE(battery_status, struct battery_status_s);
+#include "topics/servorail_status.h"
+ORB_DEFINE(servorail_status, struct servorail_status_s);
+
#include "topics/vehicle_global_position.h"
ORB_DEFINE(vehicle_global_position, struct vehicle_global_position_s);
@@ -98,27 +108,45 @@ ORB_DEFINE(rc_channels, struct rc_channels_s);
#include "topics/vehicle_command.h"
ORB_DEFINE(vehicle_command, struct vehicle_command_s);
+#include "topics/vehicle_control_mode.h"
+ORB_DEFINE(vehicle_control_mode, struct vehicle_control_mode_s);
+
#include "topics/vehicle_local_position_setpoint.h"
ORB_DEFINE(vehicle_local_position_setpoint, struct vehicle_local_position_setpoint_s);
+#include "topics/vehicle_bodyframe_speed_setpoint.h"
+ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setpoint_s);
+
#include "topics/vehicle_global_position_setpoint.h"
ORB_DEFINE(vehicle_global_position_setpoint, struct vehicle_global_position_setpoint_s);
#include "topics/vehicle_global_position_set_triplet.h"
ORB_DEFINE(vehicle_global_position_set_triplet, struct vehicle_global_position_set_triplet_s);
+#include "topics/vehicle_global_velocity_setpoint.h"
+ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setpoint_s);
+
+#include "topics/mission.h"
+ORB_DEFINE(mission, struct mission_s);
+
#include "topics/vehicle_attitude_setpoint.h"
ORB_DEFINE(vehicle_attitude_setpoint, struct vehicle_attitude_setpoint_s);
#include "topics/manual_control_setpoint.h"
ORB_DEFINE(manual_control_setpoint, struct manual_control_setpoint_s);
+#include "topics/vehicle_control_debug.h"
+ORB_DEFINE(vehicle_control_debug, struct vehicle_control_debug_s);
+
#include "topics/offboard_control_setpoint.h"
ORB_DEFINE(offboard_control_setpoint, struct offboard_control_setpoint_s);
#include "topics/optical_flow.h"
ORB_DEFINE(optical_flow, struct optical_flow_s);
+#include "topics/filtered_bottom_flow.h"
+ORB_DEFINE(filtered_bottom_flow, struct filtered_bottom_flow_s);
+
#include "topics/omnidirectional_flow.h"
ORB_DEFINE(omnidirectional_flow, struct omnidirectional_flow_s);
@@ -137,14 +165,9 @@ ORB_DEFINE(actuator_controls_0, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_1, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_2, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_3, struct actuator_controls_s);
-ORB_DEFINE(actuator_armed, struct actuator_armed_s);
-/* actuator controls, as set by actuators / mixers after limiting */
-#include "topics/actuator_controls_effective.h"
-ORB_DEFINE(actuator_controls_effective_0, struct actuator_controls_effective_s);
-ORB_DEFINE(actuator_controls_effective_1, struct actuator_controls_effective_s);
-ORB_DEFINE(actuator_controls_effective_2, struct actuator_controls_effective_s);
-ORB_DEFINE(actuator_controls_effective_3, struct actuator_controls_effective_s);
+#include "topics/actuator_armed.h"
+ORB_DEFINE(actuator_armed, struct actuator_armed_s);
#include "topics/actuator_outputs.h"
ORB_DEFINE(actuator_outputs_0, struct actuator_outputs_s);
@@ -152,5 +175,14 @@ 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/telemetry_status.h"
+ORB_DEFINE(telemetry_status, struct telemetry_status_s);
+
#include "topics/debug_key_value.h"
ORB_DEFINE(debug_key_value, struct debug_key_value_s);
+
+#include "topics/navigation_capabilities.h"
+ORB_DEFINE(navigation_capabilities, struct navigation_capabilities_s);
+
+#include "topics/esc_status.h"
+ORB_DEFINE(esc_status, struct esc_status_s);
diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h
new file mode 100644
index 000000000..6e944ffee
--- /dev/null
+++ b/src/modules/uORB/topics/actuator_armed.h
@@ -0,0 +1,58 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 actuator_armed.h
+ *
+ * Actuator armed topic
+ *
+ */
+
+#ifndef TOPIC_ACTUATOR_ARMED_H
+#define TOPIC_ACTUATOR_ARMED_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/** global 'actuator output is live' control. */
+struct actuator_armed_s {
+
+ uint64_t timestamp;
+ bool armed; /**< Set to true if system is armed */
+ bool ready_to_arm; /**< Set to true if system is ready to be armed */
+ bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
+};
+
+ORB_DECLARE(actuator_armed);
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
index b7c4196c0..e768ab2f6 100644
--- a/src/modules/uORB/topics/actuator_controls.h
+++ b/src/modules/uORB/topics/actuator_controls.h
@@ -52,27 +52,27 @@
#define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
+/* control sets with pre-defined applications */
+#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct actuator_controls_s {
uint64_t timestamp;
float control[NUM_ACTUATOR_CONTROLS];
};
+/**
+ * @}
+ */
+
/* actuator control sets; this list can be expanded as more controllers emerge */
ORB_DECLARE(actuator_controls_0);
ORB_DECLARE(actuator_controls_1);
ORB_DECLARE(actuator_controls_2);
ORB_DECLARE(actuator_controls_3);
-/* control sets with pre-defined applications */
-#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
-
-/** global 'actuator output is live' control. */
-struct actuator_armed_s {
- bool armed; /**< Set to true if system is armed */
- bool ready_to_arm; /**< Set to true if system is ready to be armed */
- bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
-};
-
-ORB_DECLARE(actuator_armed);
-
-#endif \ No newline at end of file
+#endif
diff --git a/src/modules/uORB/topics/actuator_controls_effective.h b/src/modules/uORB/topics/actuator_controls_effective.h
index 088c4fc8f..54d84231f 100644
--- a/src/modules/uORB/topics/actuator_controls_effective.h
+++ b/src/modules/uORB/topics/actuator_controls_effective.h
@@ -46,25 +46,34 @@
#ifndef TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H
#define TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H
-#include <stdint.h>
-#include "../uORB.h"
-#include "actuator_controls.h"
+//#include <stdint.h>
+//#include "../uORB.h"
+//#include "actuator_controls.h"
+//
+//#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
+//#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
+//
+///**
+// * @addtogroup topics
+// * @{
+// */
+//
+//struct actuator_controls_effective_s {
+// uint64_t timestamp;
+// float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
+//};
+//
+///**
+// * @}
+// */
+//
+///* actuator control sets; this list can be expanded as more controllers emerge */
+//ORB_DECLARE(actuator_controls_effective_0);
+//ORB_DECLARE(actuator_controls_effective_1);
+//ORB_DECLARE(actuator_controls_effective_2);
+//ORB_DECLARE(actuator_controls_effective_3);
+//
+///* control sets with pre-defined applications */
+//#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE ORB_ID(actuator_controls_effective_0)
-#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
-#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
-
-struct actuator_controls_effective_s {
- uint64_t timestamp;
- float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
-};
-
-/* actuator control sets; this list can be expanded as more controllers emerge */
-ORB_DECLARE(actuator_controls_effective_0);
-ORB_DECLARE(actuator_controls_effective_1);
-ORB_DECLARE(actuator_controls_effective_2);
-ORB_DECLARE(actuator_controls_effective_3);
-
-/* control sets with pre-defined applications */
-#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE ORB_ID(actuator_controls_effective_0)
-
-#endif /* TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H */ \ No newline at end of file
+#endif /* TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H */
diff --git a/src/modules/uORB/topics/actuator_outputs.h b/src/modules/uORB/topics/actuator_outputs.h
index bbe429073..446140423 100644
--- a/src/modules/uORB/topics/actuator_outputs.h
+++ b/src/modules/uORB/topics/actuator_outputs.h
@@ -52,12 +52,21 @@
#define NUM_ACTUATOR_OUTPUTS 16
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct actuator_outputs_s {
uint64_t timestamp; /**< output timestamp in us since system boot */
float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */
- int noutputs; /**< valid outputs */
+ unsigned noutputs; /**< valid outputs */
};
+/**
+ * @}
+ */
+
/* actuator output sets; this list can be expanded as more drivers emerge */
ORB_DECLARE(actuator_outputs_0);
ORB_DECLARE(actuator_outputs_1);
diff --git a/src/modules/uORB/topics/battery_status.h b/src/modules/uORB/topics/battery_status.h
index c40d0d4e5..d473dff3f 100644
--- a/src/modules/uORB/topics/battery_status.h
+++ b/src/modules/uORB/topics/battery_status.h
@@ -53,9 +53,10 @@
*/
struct battery_status_s {
uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
- float voltage_v; /**< Battery voltage in volts, filtered */
- float current_a; /**< Battery current in amperes, filtered, -1 if unknown */
- float discharged_mah; /**< Discharged amount in mAh, filtered, -1 if unknown */
+ float voltage_v; /**< Battery voltage in volts, 0 if unknown */
+ float voltage_filtered_v; /**< Battery voltage in volts, filtered, 0 if unknown */
+ float current_a; /**< Battery current in amperes, -1 if unknown */
+ float discharged_mah; /**< Discharged amount in mAh, -1 if unknown */
};
/**
@@ -65,4 +66,4 @@ struct battery_status_s {
/* register this as object request broker structure */
ORB_DECLARE(battery_status);
-#endif \ No newline at end of file
+#endif
diff --git a/src/modules/uORB/topics/debug_key_value.h b/src/modules/uORB/topics/debug_key_value.h
index a9d1b83fd..9253c787d 100644
--- a/src/modules/uORB/topics/debug_key_value.h
+++ b/src/modules/uORB/topics/debug_key_value.h
@@ -47,6 +47,7 @@
/**
* @addtogroup topics
+ * @{
*/
/**
diff --git a/src/modules/uORB/topics/differential_pressure.h b/src/modules/uORB/topics/differential_pressure.h
index 8ce85213b..5d94d4288 100644
--- a/src/modules/uORB/topics/differential_pressure.h
+++ b/src/modules/uORB/topics/differential_pressure.h
@@ -52,10 +52,12 @@
* Differential pressure.
*/
struct differential_pressure_s {
- uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
- uint16_t differential_pressure_pa; /**< Differential pressure reading */
- uint16_t max_differential_pressure_pa; /**< Maximum differential pressure reading */
- float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */
+ uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
+ uint64_t error_count;
+ float differential_pressure_pa; /**< Differential pressure reading */
+ float max_differential_pressure_pa; /**< Maximum differential pressure reading */
+ float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */
+ float temperature; /**< Temperature provided by sensor */
};
diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h
new file mode 100644
index 000000000..11332d7a7
--- /dev/null
+++ b/src/modules/uORB/topics/esc_status.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Marco Bauer <marco@wtns.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 esc_status.h
+ * Definition of the esc_status uORB topic.
+ *
+ * Published the state machine and the system status bitfields
+ * (see SYS_STATUS mavlink message), published only by commander app.
+ *
+ * All apps should write to subsystem_info:
+ *
+ * (any app) --> subsystem_info (published) --> (commander app state machine) --> esc_status --> (mavlink app)
+ */
+
+#ifndef ESC_STATUS_H_
+#define ESC_STATUS_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * The number of ESCs supported.
+ * Current (Q2/2013) we support 8 ESCs,
+ */
+#define CONNECTED_ESC_MAX 8
+
+enum ESC_VENDOR {
+ ESC_VENDOR_GENERIC = 0, /**< generic ESC */
+ ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
+ ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
+};
+
+enum ESC_CONNECTION_TYPE {
+ ESC_CONNECTION_TYPE_PPM = 0, /**< Traditional PPM ESC */
+ ESC_CONNECTION_TYPE_SERIAL, /**< Serial Bus connected ESC */
+ ESC_CONNECTION_TYPE_ONESHOOT, /**< One Shoot PPM */
+ ESC_CONNECTION_TYPE_I2C, /**< I2C */
+ ESC_CONNECTION_TYPE_CAN /**< CAN-Bus */
+};
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Electronic speed controller status.
+ */
+struct esc_status_s
+{
+ /* use of a counter and timestamp recommended (but not necessary) */
+
+ uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+
+ uint8_t esc_count; /**< number of connected ESCs */
+ 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 */
+ 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 */
+ } esc[CONNECTED_ESC_MAX];
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+//ORB_DECLARE(esc_status);
+ORB_DECLARE_OPTIONAL(esc_status);
+
+#endif
diff --git a/src/modules/mathlib/math/Vector3.cpp b/src/modules/uORB/topics/filtered_bottom_flow.h
index 61fcc442f..ab6de2613 100644
--- a/src/modules/mathlib/math/Vector3.cpp
+++ b/src/modules/uORB/topics/filtered_bottom_flow.h
@@ -1,6 +1,8 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,68 +34,41 @@
****************************************************************************/
/**
- * @file Vector3.cpp
- *
- * math vector
+ * @file filtered_bottom_flow.h
+ * Definition of the filtered bottom flow uORB topic.
*/
-#include "test/test.hpp"
-
-#include "Vector3.hpp"
+#ifndef TOPIC_FILTERED_BOTTOM_FLOW_H_
+#define TOPIC_FILTERED_BOTTOM_FLOW_H_
-namespace math
-{
-
-Vector3::Vector3() :
- Vector(3)
-{
-}
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
-Vector3::Vector3(const Vector &right) :
- Vector(right)
-{
-#ifdef VECTOR_ASSERT
- ASSERT(right.getRows() == 3);
-#endif
-}
+/**
+ * @addtogroup topics
+ * @{
+ */
-Vector3::Vector3(float x, float y, float z) :
- Vector(3)
+/**
+ * Filtered bottom flow in bodyframe.
+ */
+struct filtered_bottom_flow_s
{
- setX(x);
- setY(y);
- setZ(z);
-}
+ uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
-Vector3::Vector3(const float *data) :
- Vector(3, data)
-{
-}
+ float sumx; /**< Integrated bodyframe x flow in meters */
+ float sumy; /**< Integrated bodyframe y flow in meters */
-Vector3::~Vector3()
-{
-}
+ float vx; /**< Flow bodyframe x speed, m/s */
+ float vy; /**< Flow bodyframe y Speed, m/s */
+};
-Vector3 Vector3::cross(const Vector3 &b)
-{
- Vector3 &a = *this;
- Vector3 result;
- result(0) = a(1) * b(2) - a(2) * b(1);
- result(1) = a(2) * b(0) - a(0) * b(2);
- result(2) = a(0) * b(1) - a(1) * b(0);
- return result;
-}
+/**
+ * @}
+ */
-int __EXPORT vector3Test()
-{
- printf("Test Vector3\t\t: ");
- // test float ctor
- Vector3 v(1, 2, 3);
- ASSERT(equal(v(0), 1));
- ASSERT(equal(v(1), 2));
- ASSERT(equal(v(2), 3));
- printf("PASS\n");
- return 0;
-}
+/* register this as object request broker structure */
+ORB_DECLARE(filtered_bottom_flow);
-} // namespace math
+#endif
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index 261a8a4ad..eac6d6e98 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -56,17 +56,18 @@ struct manual_control_setpoint_s {
float yaw; /**< rudder / yaw rate / yaw */
float throttle; /**< throttle / collective thrust / altitude */
- float manual_override_switch; /**< manual override mode (mandatory) */
- float auto_mode_switch; /**< auto mode switch (mandatory) */
+ float mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
+ float return_switch; /**< land 2 position switch (mandatory): land, no effect */
+ float assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
+ float mission_switch; /**< mission 2 position switch (optional): mission, loiter */
/**
* Any of the channels below may not be available and be set to NaN
* to indicate that it does not contain valid data.
*/
- float manual_mode_switch; /**< manual mode (man, sas, alt) switch (optional) */
- float manual_sas_switch; /**< sas mode (rates / attitude) switch (optional) */
- float return_to_launch_switch; /**< return to launch switch (0 = disabled, 1 = enabled) */
- float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
+
+ // XXX needed or parameter?
+ //float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
float flaps; /**< flap position */
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
new file mode 100644
index 000000000..978a3383a
--- /dev/null
+++ b/src/modules/uORB/topics/mission.h
@@ -0,0 +1,99 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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>
+ *
+ * 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 mission_item.h
+ * Definition of one mission item.
+ */
+
+#ifndef TOPIC_MISSION_H_
+#define TOPIC_MISSION_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+enum NAV_CMD {
+ NAV_CMD_WAYPOINT = 0,
+ NAV_CMD_LOITER_TURN_COUNT,
+ NAV_CMD_LOITER_TIME_LIMIT,
+ NAV_CMD_LOITER_UNLIMITED,
+ NAV_CMD_RETURN_TO_LAUNCH,
+ NAV_CMD_LAND,
+ NAV_CMD_TAKEOFF
+};
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Global position setpoint in WGS84 coordinates.
+ *
+ * This is the position the MAV is heading towards. If it of type loiter,
+ * the MAV is circling around it with the given loiter radius in meters.
+ */
+struct mission_item_s
+{
+ bool altitude_is_relative; /**< true if altitude is relative from start point */
+ double lat; /**< latitude in degrees * 1E7 */
+ double lon; /**< longitude in degrees * 1E7 */
+ float altitude; /**< altitude in meters */
+ float yaw; /**< in radians NED -PI..+PI */
+ float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
+ uint8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
+ enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+};
+
+struct mission_s
+{
+ struct mission_item_s *items;
+ unsigned count;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(mission);
+
+#endif
diff --git a/src/modules/uORB/topics/navigation_capabilities.h b/src/modules/uORB/topics/navigation_capabilities.h
new file mode 100644
index 000000000..6a3e811e3
--- /dev/null
+++ b/src/modules/uORB/topics/navigation_capabilities.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ *
+ * 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 navigation_capabilities.h
+ *
+ * Definition of navigation capabilities uORB topic.
+ */
+
+#ifndef TOPIC_NAVIGATION_CAPABILITIES_H_
+#define TOPIC_NAVIGATION_CAPABILITIES_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Airspeed
+ */
+struct navigation_capabilities_s {
+ float turn_distance; /**< the optimal distance to a waypoint to switch to the next */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(navigation_capabilities);
+
+#endif
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index 2e895c59c..7901b930a 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -44,11 +44,6 @@
#include "../uORB.h"
/**
- * @addtogroup topics
- * @{
- */
-
-/**
* Off-board control inputs.
*
* Typically sent by a ground control station / joystick or by
@@ -66,6 +61,11 @@ enum OFFBOARD_CONTROL_MODE
OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct offboard_control_setpoint_s {
uint64_t timestamp;
diff --git a/src/modules/uORB/topics/omnidirectional_flow.h b/src/modules/uORB/topics/omnidirectional_flow.h
index 8f4be3b3f..a6ad8a131 100644
--- a/src/modules/uORB/topics/omnidirectional_flow.h
+++ b/src/modules/uORB/topics/omnidirectional_flow.h
@@ -46,6 +46,7 @@
/**
* @addtogroup topics
+ * @{
*/
/**
diff --git a/src/modules/uORB/topics/optical_flow.h b/src/modules/uORB/topics/optical_flow.h
index c854f0079..98f0e3fa2 100644
--- a/src/modules/uORB/topics/optical_flow.h
+++ b/src/modules/uORB/topics/optical_flow.h
@@ -57,8 +57,8 @@ struct optical_flow_s {
uint64_t timestamp; /**< in microseconds since system start */
- uint16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
- uint16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
+ 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, rotation-compensated */
float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
float ground_distance_m; /**< Altitude / distance to ground in meters */
diff --git a/src/modules/uORB/topics/parameter_update.h b/src/modules/uORB/topics/parameter_update.h
index 300e895c7..68964deb0 100644
--- a/src/modules/uORB/topics/parameter_update.h
+++ b/src/modules/uORB/topics/parameter_update.h
@@ -42,11 +42,20 @@
#include <stdint.h>
#include "../uORB.h"
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct parameter_update_s {
/** time at which the latest parameter was updated */
uint64_t timestamp;
};
+/**
+ * @}
+ */
+
ORB_DECLARE(parameter_update);
#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 9dd54df91..086b2ef15 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Nils Wenzler <wenzlern@student.ethz.ch>
- * @author Ivan Ovinnikov <oivan@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -46,16 +43,14 @@
#include "../uORB.h"
/**
- * @addtogroup topics
- * @{
- */
-
-/**
* The number of RC channel inputs supported.
- * Current (Q1/2013) radios support up to 18 channels,
- * leaving at a sane value of 14.
+ * Current (Q4/2013) radios support up to 18 channels,
+ * leaving at a sane value of 15.
+ * This number can be greater then number of RC channels,
+ * because single RC channel can be mapped to multiple
+ * functions, e.g. for various mode switches.
*/
-#define RC_CHANNELS_MAX 14
+#define RC_CHANNELS_MAPPED_MAX 15
/**
* This defines the mapping of the RC functions.
@@ -68,28 +63,32 @@ enum RC_CHANNELS_FUNCTION
ROLL = 1,
PITCH = 2,
YAW = 3,
- OVERRIDE = 4,
- AUTO_MODE = 5,
- MANUAL_MODE = 6,
- SAS_MODE = 7,
- RTL = 8,
- OFFBOARD_MODE = 9,
- FLAPS = 10,
- AUX_1 = 11,
- AUX_2 = 12,
- AUX_3 = 13,
- AUX_4 = 14,
- AUX_5 = 15,
+ MODE = 4,
+ RETURN = 5,
+ ASSISTED = 6,
+ MISSION = 7,
+ OFFBOARD_MODE = 8,
+ FLAPS = 9,
+ AUX_1 = 10,
+ AUX_2 = 11,
+ AUX_3 = 12,
+ AUX_4 = 13,
+ AUX_5 = 14,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct rc_channels_s {
uint64_t timestamp; /**< In microseconds since boot time. */
uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
struct {
float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
- } chan[RC_CHANNELS_MAX];
+ } chan[RC_CHANNELS_MAPPED_MAX];
uint8_t chan_count; /**< number of valid channels */
/*String array to store the names of the functions*/
diff --git a/src/modules/mathlib/math/Matrix.hpp b/src/modules/uORB/topics/safety.h
index f19db15ec..a5d21cd4a 100644
--- a/src/modules/mathlib/math/Matrix.hpp
+++ b/src/modules/uORB/topics/safety.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 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
@@ -32,30 +32,26 @@
****************************************************************************/
/**
- * @file Matrix.h
+ * @file safety.h
*
- * matrix code
+ * Safety topic to pass safety state from px4io driver to commander
+ * This concerns only the safety button of the px4io but has nothing to do
+ * with arming/disarming.
*/
-#pragma once
+#ifndef TOPIC_SAFETY_H
+#define TOPIC_SAFETY_H
-#include <nuttx/config.h>
+#include <stdint.h>
+#include "../uORB.h"
-#if defined(CONFIG_ARCH_CORTEXM4) && defined(CONFIG_ARCH_FPU)
-#include "arm/Matrix.hpp"
-#else
-#include "generic/Matrix.hpp"
-#endif
+struct safety_s {
-namespace math
-{
-class Matrix;
-int matrixTest();
-int matrixAddTest();
-int matrixSubTest();
-int matrixMultTest();
-int matrixInvTest();
-int matrixDivTest();
-int matrixArmTest();
-bool matrixEqual(const Matrix &a, const Matrix &b, float eps = 1.0e-5f);
-} // namespace math
+ uint64_t timestamp;
+ bool safety_switch_available; /**< Set to true if a safety switch is connected */
+ bool safety_off; /**< Set to true if safety is off */
+};
+
+ORB_DECLARE(safety);
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index 9a76b5182..ad164555e 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -46,11 +46,6 @@
#include <stdbool.h>
#include "../uORB.h"
-/**
- * @addtogroup topics
- * @{
- */
-
enum MAGNETOMETER_MODE {
MAGNETOMETER_MODE_NORMAL = 0,
MAGNETOMETER_MODE_POSITIVE_BIAS,
@@ -58,6 +53,11 @@ enum MAGNETOMETER_MODE {
};
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Sensor readings in raw and SI-unit form.
*
* These values are read from the sensors. Raw values are in sensor-specific units,
diff --git a/src/modules/uORB/topics/servorail_status.h b/src/modules/uORB/topics/servorail_status.h
new file mode 100644
index 000000000..55668790b
--- /dev/null
+++ b/src/modules/uORB/topics/servorail_status.h
@@ -0,0 +1,67 @@
+/****************************************************************************
+ *
+ * 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 servorail_status.h
+ *
+ * Definition of the servorail status uORB topic.
+ */
+
+#ifndef SERVORAIL_STATUS_H_
+#define SERVORAIL_STATUS_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Servorail voltages and status
+ */
+struct servorail_status_s {
+ uint64_t timestamp; /**< microseconds since system boot */
+ float voltage_v; /**< Servo rail voltage in volts */
+ float rssi_v; /**< RSSI pin voltage in volts */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(servorail_status);
+
+#endif
diff --git a/src/modules/uORB/topics/subsystem_info.h b/src/modules/uORB/topics/subsystem_info.h
index c415e832e..cfe0bf69e 100644
--- a/src/modules/uORB/topics/subsystem_info.h
+++ b/src/modules/uORB/topics/subsystem_info.h
@@ -50,10 +50,6 @@
#include <stdbool.h>
#include "../uORB.h"
-/**
- * @addtogroup topics
- */
-
enum SUBSYSTEM_TYPE
{
SUBSYSTEM_TYPE_GYRO = 1,
@@ -76,6 +72,10 @@ enum SUBSYSTEM_TYPE
};
/**
+ * @addtogroup topics
+ */
+
+/**
* State of individual sub systems
*/
struct subsystem_info_s {
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
new file mode 100644
index 000000000..828fb31cc
--- /dev/null
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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 telemetry_status.h
+ *
+ * Telemetry status topics - radio status outputs
+ */
+
+#ifndef TOPIC_TELEMETRY_STATUS_H
+#define TOPIC_TELEMETRY_STATUS_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+enum TELEMETRY_STATUS_RADIO_TYPE {
+ TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0,
+ TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO,
+ TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET,
+ TELEMETRY_STATUS_RADIO_TYPE_WIRE
+};
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct telemetry_status_s {
+ uint64_t timestamp;
+ enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
+ unsigned rssi; /**< local signal strength */
+ unsigned remote_rssi; /**< remote signal strength */
+ unsigned rxerrors; /**< receive errors */
+ unsigned fixed; /**< count of error corrected packets */
+ 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 */
+};
+
+/**
+ * @}
+ */
+
+ORB_DECLARE(telemetry_status);
+
+#endif /* TOPIC_TELEMETRY_STATUS_H */ \ No newline at end of file
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
index c31c81d0c..4380a5ee7 100755
--- a/src/modules/uORB/topics/vehicle_attitude.h
+++ b/src/modules/uORB/topics/vehicle_attitude.h
@@ -48,6 +48,7 @@
/**
* @addtogroup topics
+ * @{
*/
/**
diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
index a7cda34a8..1a245132a 100644
--- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
@@ -64,8 +64,16 @@ struct vehicle_attitude_setpoint_s
float R_body[9]; /**< Rotation matrix describing the setpoint as rotation from the current body frame */
bool R_valid; /**< Set to true if rotation matrix is valid */
+ //! For quaternion-based attitude control
+ float q_d[4]; /** Desired quaternion for quaternion control */
+ bool q_d_valid; /**< Set to true if quaternion vector is valid */
+ float q_e[4]; /** Attitude error in quaternion */
+ bool q_e_valid; /**< Set to true if quaternion error vector is valid */
+
float thrust; /**< Thrust in Newton the power system should generate */
+ bool roll_reset_integral; /**< Reset roll integral part (navigation logic change) */
+
};
/**
diff --git a/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h b/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
new file mode 100644
index 000000000..fbfab09f3
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
@@ -0,0 +1,69 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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 vehicle_bodyframe_speed_setpoint.h
+ * Definition of the bodyframe speed setpoint uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_BODYFRAME_SPEED_SETPOINT_H_
+#define TOPIC_VEHICLE_BODYFRAME_SPEED_SETPOINT_H_
+
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct vehicle_bodyframe_speed_setpoint_s
+{
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+
+ float vx; /**< in m/s */
+ float vy; /**< in m/s */
+// float vz; /**< in m/s */
+ float thrust_sp;
+ float yaw_sp; /**< in radian -PI +PI */
+}; /**< Speed in bodyframe to go to */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_bodyframe_speed_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index fac571659..e6e4743c6 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -46,11 +46,6 @@
#include "../uORB.h"
/**
- * @addtogroup topics
- * @{
- */
-
-/**
* Commands for commander app.
*
* Should contain all commands from MAVLink's VEHICLE_CMD ENUM,
@@ -91,7 +86,8 @@ enum VEHICLE_CMD
VEHICLE_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
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_ENUM_END=401, /* | */
+ VEHICLE_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ VEHICLE_CMD_ENUM_END=501, /* | */
};
/**
@@ -110,6 +106,10 @@ enum VEHICLE_CMD_RESULT
VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
struct vehicle_command_s
{
@@ -120,7 +120,7 @@ struct vehicle_command_s
float param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
float param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */
- uint16_t command; /**< Command ID, as defined MAVLink by 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 */
uint8_t target_component; /**< Component which should execute the command, 0 for all components */
uint8_t source_system; /**< System sending the command */
diff --git a/src/modules/uORB/topics/vehicle_control_debug.h b/src/modules/uORB/topics/vehicle_control_debug.h
new file mode 100644
index 000000000..6184284a4
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_control_debug.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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 vehicle_control_debug.h
+ * For debugging purposes to log PID parts of controller
+ */
+
+#ifndef TOPIC_VEHICLE_CONTROL_DEBUG_H_
+#define TOPIC_VEHICLE_CONTROL_DEBUG_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+struct vehicle_control_debug_s
+{
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ float roll_p; /**< roll P control part */
+ float roll_i; /**< roll I control part */
+ float roll_d; /**< roll D control part */
+
+ float roll_rate_p; /**< roll rate P control part */
+ float roll_rate_i; /**< roll rate I control part */
+ float roll_rate_d; /**< roll rate D control part */
+
+ float pitch_p; /**< pitch P control part */
+ float pitch_i; /**< pitch I control part */
+ float pitch_d; /**< pitch D control part */
+
+ float pitch_rate_p; /**< pitch rate P control part */
+ float pitch_rate_i; /**< pitch rate I control part */
+ float pitch_rate_d; /**< pitch rate D control part */
+
+ float yaw_p; /**< yaw P control part */
+ float yaw_i; /**< yaw I control part */
+ float yaw_d; /**< yaw D control part */
+
+ float yaw_rate_p; /**< yaw rate P control part */
+ float yaw_rate_i; /**< yaw rate I control part */
+ float yaw_rate_d; /**< yaw rate D control part */
+
+}; /**< vehicle_control_debug */
+
+ /**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_control_debug);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
new file mode 100644
index 000000000..38fb74c9b
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 vehicle_control_mode.h
+ * Definition of the vehicle_control_mode uORB topic.
+ *
+ * All control apps should depend their actions based on the flags set here.
+ */
+
+#ifndef VEHICLE_CONTROL_MODE
+#define VEHICLE_CONTROL_MODE
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics @{
+ */
+
+
+/**
+ * state machine / state of vehicle.
+ *
+ * Encodes the complete system state and is set by the commander app.
+ */
+struct vehicle_control_mode_s
+{
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+
+ bool flag_armed;
+
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
+
+ // XXX needs yet to be set by state machine helper
+ bool flag_system_hil_enabled;
+
+ bool flag_control_manual_enabled; /**< true if manual input is mixed in */
+ bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ 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_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 */
+ bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */
+
+ bool flag_control_auto_enabled; // TEMP
+ uint8_t auto_state; // TEMP navigation state for AUTO modes
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_control_mode);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index f036c7223..143734e37 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -62,18 +62,17 @@
struct vehicle_global_position_s
{
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
- uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
- bool valid; /**< true if position satisfies validity criteria of estimator */
-
- int32_t lat; /**< Latitude in 1E7 degrees LOGME */
- int32_t lon; /**< Longitude in 1E7 degrees LOGME */
- float alt; /**< Altitude in meters LOGME */
- float relative_alt; /**< Altitude above home position in meters, LOGME */
- float vx; /**< Ground X Speed (Latitude), m/s in ENU LOGME */
- float vy; /**< Ground Y Speed (Longitude), m/s in ENU LOGME */
- float vz; /**< Ground Z Speed (Altitude), m/s in ENU LOGME */
- float hdg; /**< Compass heading in radians -PI..+PI. */
+ uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
+ bool valid; /**< true if position satisfies validity criteria of estimator */
+ int32_t lat; /**< Latitude in 1E7 degrees */
+ int32_t lon; /**< Longitude in 1E7 degrees */
+ float alt; /**< Altitude in meters */
+ float relative_alt; /**< Altitude above home position in meters, */
+ float vx; /**< Ground X velocity, m/s in NED */
+ float vy; /**< Ground Y velocity, m/s in NED */
+ float vz; /**< Ground Z velocity, m/s in NED */
+ float yaw; /**< Compass heading in radians -PI..+PI. */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
index 318abba89..8516b263f 100644
--- a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
+++ b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
@@ -60,8 +60,8 @@
*/
struct vehicle_global_position_set_triplet_s
{
- bool previous_valid;
- bool next_valid;
+ bool previous_valid; /**< flag indicating previous position is valid */
+ bool next_valid; /**< flag indicating next position is valid */
struct vehicle_global_position_setpoint_s previous;
struct vehicle_global_position_setpoint_s current;
diff --git a/src/modules/uORB/topics/vehicle_global_position_setpoint.h b/src/modules/uORB/topics/vehicle_global_position_setpoint.h
index eec6a8229..a56434d3b 100644
--- a/src/modules/uORB/topics/vehicle_global_position_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_global_position_setpoint.h
@@ -45,6 +45,7 @@
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
+#include "mission.h"
/**
* @addtogroup topics
@@ -65,7 +66,14 @@ struct vehicle_global_position_setpoint_s
float altitude; /**< altitude in meters */
float yaw; /**< in radians NED -PI..+PI */
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
- bool is_loiter; /**< true if loitering is enabled */
+ int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
+ enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+ float turn_distance_xy; /**< The distance on the plane which will mark this as reached */
+ float turn_distance_z; /**< The distance in Z direction which will mark this as reached */
};
/**
diff --git a/src/modules/mathlib/math/Vector3.hpp b/src/modules/uORB/topics/vehicle_global_velocity_setpoint.h
index 8c36ac134..73961cdfe 100644
--- a/src/modules/mathlib/math/Vector3.hpp
+++ b/src/modules/uORB/topics/vehicle_global_velocity_setpoint.h
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,40 +33,32 @@
****************************************************************************/
/**
- * @file Vector3.hpp
- *
- * math 3 vector
+ * @file vehicle_global_velocity_setpoint.h
+ * Definition of the global velocity setpoint uORB topic.
*/
-#pragma once
+#ifndef TOPIC_VEHICLE_GLOBAL_VELOCITY_SETPOINT_H_
+#define TOPIC_VEHICLE_GLOBAL_VELOCITY_SETPOINT_H_
-#include "Vector.hpp"
+#include "../uORB.h"
-namespace math
-{
+/**
+ * @addtogroup topics
+ * @{
+ */
-class __EXPORT Vector3 :
- public Vector
+struct vehicle_global_velocity_setpoint_s
{
-public:
- Vector3();
- Vector3(const Vector &right);
- Vector3(float x, float y, float z);
- Vector3(const float *data);
- virtual ~Vector3();
- Vector3 cross(const Vector3 &b);
+ float vx; /**< in m/s NED */
+ float vy; /**< in m/s NED */
+ float vz; /**< in m/s NED */
+}; /**< Velocity setpoint in NED frame */
- /**
- * accessors
- */
- void setX(float x) { (*this)(0) = x; }
- void setY(float y) { (*this)(1) = y; }
- void setZ(float z) { (*this)(2) = z; }
- const float &getX() const { return (*this)(0); }
- const float &getY() const { return (*this)(1); }
- const float &getZ() const { return (*this)(2); }
-};
+/**
+ * @}
+ */
-int __EXPORT vector3Test();
-} // math
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_global_velocity_setpoint);
+#endif
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 0a7fb4e9d..1639a08c2 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -56,9 +56,9 @@
struct vehicle_gps_position_s
{
uint64_t timestamp_position; /**< Timestamp for position information */
- int32_t lat; /**< Latitude in 1E7 degrees */
- int32_t lon; /**< Longitude in 1E7 degrees */
- int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
+ int32_t lat; /**< Latitude in 1E-7 degrees */
+ int32_t lon; /**< Longitude in 1E-7 degrees */
+ int32_t alt; /**< Altitude in 1E-3 meters (millimeters) above MSL */
uint64_t timestamp_variance;
float s_variance_m_s; /**< speed accuracy estimate m/s */
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index 76eddeacd..427153782 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -54,27 +54,29 @@
*/
struct vehicle_local_position_s
{
- uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
- bool valid; /**< true if position satisfies validity criteria of estimator */
-
- float x; /**< X positin in meters in NED earth-fixed frame */
- float y; /**< X positin in meters in NED earth-fixed frame */
- float z; /**< Z positin in meters in NED earth-fixed frame (negative altitude) */
- float absolute_alt; /**< Altitude as defined by pressure / GPS, LOGME */
- float vx; /**< Ground X Speed (Latitude), m/s in NED LOGME */
- float vy; /**< Ground Y Speed (Longitude), m/s in NED LOGME */
- float vz; /**< Ground Z Speed (Altitude), m/s in NED LOGME */
- float hdg; /**< Compass heading in radians -PI..+PI. */
-
- // TODO Add covariances here
-
+ uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
+ bool xy_valid; /**< true if x and y are valid */
+ bool z_valid; /**< true if z is valid */
+ bool v_xy_valid; /**< true if vy and vy are valid */
+ bool v_z_valid; /**< true if vz is valid */
+ /* Position in local NED frame */
+ float x; /**< X position in meters in NED earth-fixed frame */
+ float y; /**< X position in meters in NED earth-fixed frame */
+ float z; /**< Z position in meters in NED earth-fixed frame (negative altitude) */
+ /* Velocity in NED frame */
+ float vx; /**< Ground X Speed (Latitude), m/s in NED */
+ float vy; /**< Ground Y Speed (Longitude), m/s in NED */
+ float vz; /**< Ground Z Speed (Altitude), m/s in NED */
+ /* Heading */
+ float yaw;
/* Reference position in GPS / WGS84 frame */
- uint64_t home_timestamp;/**< Time when home position was set */
- int32_t home_lat; /**< Latitude in 1E7 degrees LOGME */
- int32_t home_lon; /**< Longitude in 1E7 degrees LOGME */
- float home_alt; /**< Altitude in meters LOGME */
- float home_hdg; /**< Compass heading in radians -PI..+PI. */
-
+ bool xy_global; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */
+ bool z_global; /**< true if z is valid and has valid global reference (ref_alt) */
+ uint64_t ref_timestamp; /**< Time when reference position was set */
+ int32_t ref_lat; /**< Reference point latitude in 1E7 degrees */
+ int32_t ref_lon; /**< Reference point longitude in 1E7 degrees */
+ float ref_alt; /**< Reference altitude AMSL in meters, MUST be set to current (not at reference point!) ground level */
+ bool landed; /**< true if vehicle is landed */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c7c1048f6..6ea48a680 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -58,22 +58,63 @@
* @addtogroup topics @{
*/
-/* State Machine */
-typedef enum
-{
- SYSTEM_STATE_PREFLIGHT = 0,
- SYSTEM_STATE_STANDBY = 1,
- SYSTEM_STATE_GROUND_READY = 2,
- SYSTEM_STATE_MANUAL = 3,
- SYSTEM_STATE_STABILIZED = 4,
- SYSTEM_STATE_AUTO = 5,
- SYSTEM_STATE_MISSION_ABORT = 6,
- SYSTEM_STATE_EMCY_LANDING = 7,
- SYSTEM_STATE_EMCY_CUTOFF = 8,
- SYSTEM_STATE_GROUND_ERROR = 9,
- SYSTEM_STATE_REBOOT= 10,
-
-} commander_state_machine_t;
+/* main state machine */
+typedef enum {
+ MAIN_STATE_MANUAL = 0,
+ MAIN_STATE_SEATBELT,
+ MAIN_STATE_EASY,
+ MAIN_STATE_AUTO,
+} main_state_t;
+
+/* navigation state machine */
+typedef enum {
+ NAVIGATION_STATE_DIRECT = 0, // true manual control, no any stabilization
+ NAVIGATION_STATE_STABILIZE, // attitude stabilization
+ NAVIGATION_STATE_ALTHOLD, // attitude + altitude stabilization
+ NAVIGATION_STATE_VECTOR, // attitude + altitude + position stabilization
+ NAVIGATION_STATE_AUTO_READY, // AUTO, landed, reeady for takeoff
+ NAVIGATION_STATE_AUTO_TAKEOFF, // detect takeoff using land detector and switch to desired AUTO mode
+ NAVIGATION_STATE_AUTO_LOITER, // pause mission
+ NAVIGATION_STATE_AUTO_MISSION, // fly mission
+ NAVIGATION_STATE_AUTO_RTL, // Return To Launch, when home position switch to LAND
+ NAVIGATION_STATE_AUTO_LAND // land and switch to AUTO_READY when landed (detect using land detector)
+} navigation_state_t;
+
+typedef enum {
+ ARMING_STATE_INIT = 0,
+ ARMING_STATE_STANDBY,
+ ARMING_STATE_ARMED,
+ ARMING_STATE_ARMED_ERROR,
+ ARMING_STATE_STANDBY_ERROR,
+ ARMING_STATE_REBOOT,
+ ARMING_STATE_IN_AIR_RESTORE
+} arming_state_t;
+
+typedef enum {
+ HIL_STATE_OFF = 0,
+ HIL_STATE_ON
+} hil_state_t;
+
+typedef enum {
+ MODE_SWITCH_MANUAL = 0,
+ MODE_SWITCH_ASSISTED,
+ MODE_SWITCH_AUTO
+} mode_switch_pos_t;
+
+typedef enum {
+ ASSISTED_SWITCH_SEATBELT = 0,
+ ASSISTED_SWITCH_EASY
+} assisted_switch_pos_t;
+
+typedef enum {
+ RETURN_SWITCH_NONE = 0,
+ RETURN_SWITCH_RETURN
+} return_switch_pos_t;
+
+typedef enum {
+ MISSION_SWITCH_NONE = 0,
+ MISSION_SWITCH_MISSION
+} mission_switch_pos_t;
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
@@ -86,26 +127,6 @@ enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
}; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */
-enum VEHICLE_FLIGHT_MODE {
- VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, exact mode determined by VEHICLE_MANUAL_CONTROL_MODE */
- VEHICLE_FLIGHT_MODE_STAB, /**< attitude or rate stabilization plus velocity or position stabilization */
- VEHICLE_FLIGHT_MODE_HOLD, /**< hold current position (hover or loiter around position when switched) */
- VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
-};
-
-enum VEHICLE_MANUAL_CONTROL_MODE {
- VEHICLE_MANUAL_CONTROL_MODE_DIRECT = 0, /**< no attitude control, direct stick input mixing (only fixed wing) */
- VEHICLE_MANUAL_CONTROL_MODE_RATES, /**< body rates control mode */
- VEHICLE_MANUAL_CONTROL_MODE_SAS /**< stability augmented system (SAS) mode */
-};
-
-enum VEHICLE_MANUAL_SAS_MODE {
- VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS = 0, /**< roll, pitch and yaw absolute */
- VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE, /**< roll and pitch absolute, yaw rate */
- VEHICLE_MANUAL_SAS_MODE_SIMPLE, /**< simple mode (includes altitude hold) */
- VEHICLE_MANUAL_SAS_MODE_ALTITUDE /**< altitude hold */
-};
-
/**
* Should match 1:1 MAVLink's MAV_TYPE ENUM
*/
@@ -132,11 +153,15 @@ enum VEHICLE_TYPE {
};
enum VEHICLE_BATTERY_WARNING {
- VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
- VEHICLE_BATTERY_WARNING_WARNING, /**< warning of low voltage 1. stage */
- VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
+ VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
+ VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
+ VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
/**
* state machine / state of vehicle.
@@ -149,55 +174,55 @@ struct vehicle_status_s
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
- uint64_t failsave_lowlevel_start_time; /**< time when the lowlevel failsafe flag was set */
- //uint64_t failsave_highlevel_begin; TO BE COMPLETED
- commander_state_machine_t state_machine; /**< current flight state, main state machine */
- enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
- enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
- enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */
+ main_state_t main_state; /**< main state machine */
+ navigation_state_t navigation_state; /**< navigation state machine */
+ arming_state_t arming_state; /**< current arming state */
+ hil_state_t hil_state; /**< current hil state */
+
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
int32_t component_id; /**< subsystem / component id, inspired by MAVLink's component ID field */
- /* system flags - these represent the state predicates */
-
- bool flag_system_armed; /**< true is motors / actuators are armed */
- bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_control_offboard_enabled; /**< true if offboard control input is on */
- bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
-
- 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_velocity_enabled; /**< true if speed (implies direction) is controlled */
- bool flag_control_position_enabled; /**< true if position is controlled */
-
- bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
- bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
- bool flag_preflight_accel_calibration;
- bool flag_preflight_airspeed_calibration;
+ bool is_rotary_wing;
+
+ mode_switch_pos_t mode_switch;
+ return_switch_pos_t return_switch;
+ assisted_switch_pos_t assisted_switch;
+ mission_switch_pos_t mission_switch;
+
+ bool condition_battery_voltage_valid;
+ bool condition_system_in_air_restore; /**< true if we can restore in mid air */
+ bool condition_system_sensors_initialized;
+ bool condition_system_returned_to_home;
+ bool condition_auto_mission_available;
+ bool condition_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
+ bool condition_launch_position_valid; /**< indicates a valid launch position */
+ bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+ bool condition_local_position_valid;
+ bool condition_local_altitude_valid;
+ bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
+ bool condition_landed; /**< true if vehicle is landed, always true if disarmed */
bool rc_signal_found_once;
- bool rc_signal_lost; /**< true if RC reception is terminally lost */
- bool rc_signal_cutting_off; /**< true if RC reception is weak / cutting off */
- uint64_t rc_signal_lost_interval; /**< interval in microseconds since when no RC signal is available */
+ bool rc_signal_lost; /**< true if RC reception lost */
+ bool rc_input_blocked; /**< set if RC input should be ignored */
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 failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */
- //bool failsave_highlevel;
-
/* see SYS_STATUS mavlink message for the following */
uint32_t onboard_control_sensors_present;
uint32_t onboard_control_sensors_enabled;
uint32_t onboard_control_sensors_health;
- float load;
- float voltage_battery;
- float current_battery;
+
+ float load; /**< processor load from 0 to 1 */
+ float battery_voltage;
+ float battery_current;
float battery_remaining;
+
enum VEHICLE_BATTERY_WARNING battery_warning; /**< current battery warning mode, as defined by VEHICLE_BATTERY_WARNING enum */
uint16_t drop_rate_comm;
uint16_t errors_comm;
@@ -205,15 +230,6 @@ struct vehicle_status_s
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
-
- bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
- bool flag_local_position_valid;
- bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
- bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
- bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
- bool flag_valid_launch_position; /**< indicates a valid launch position */
- bool flag_valid_home_position; /**< indicates a valid home position (a valid home position is not always a valid launch) */
- bool flag_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
};
/**
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 7abbf42ae..149b8f6d2 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -249,8 +249,10 @@ ORBDevNode::close(struct file *filp)
} else {
SubscriberData *sd = filp_to_sd(filp);
- if (sd != nullptr)
+ if (sd != nullptr) {
+ hrt_cancel(&sd->update_call);
delete sd;
+ }
}
return CDev::close(filp);
diff --git a/src/modules/unit_test/module.mk b/src/modules/unit_test/module.mk
new file mode 100644
index 000000000..f00b0f592
--- /dev/null
+++ b/src/modules/unit_test/module.mk
@@ -0,0 +1,39 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Makefile to build the unit test library.
+#
+
+SRCS = unit_test.cpp
+
diff --git a/src/modules/unit_test/unit_test.cpp b/src/modules/unit_test/unit_test.cpp
new file mode 100644
index 000000000..64ee544a2
--- /dev/null
+++ b/src/modules/unit_test/unit_test.cpp
@@ -0,0 +1,65 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 unit_test.cpp
+ * A unit test library.
+ *
+ */
+
+#include "unit_test.h"
+
+#include <systemlib/err.h>
+
+
+UnitTest::UnitTest()
+{
+}
+
+UnitTest::~UnitTest()
+{
+}
+
+void
+UnitTest::print_results(const char* result)
+{
+ if (result != 0) {
+ warnx("Failed: %s:%d", mu_last_test(), mu_line());
+ warnx("%s", result);
+ } else {
+ warnx("ALL TESTS PASSED");
+ warnx(" Tests run : %d", mu_tests_run());
+ warnx(" Assertion : %d", mu_assertion());
+ }
+}
diff --git a/src/modules/unit_test/unit_test.h b/src/modules/unit_test/unit_test.h
new file mode 100644
index 000000000..3020734f4
--- /dev/null
+++ b/src/modules/unit_test/unit_test.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 unit_test.h
+ * A unit test library based on MinUnit (http://www.jera.com/techinfo/jtns/jtn002.html).
+ *
+ */
+
+#ifndef UNIT_TEST_H_
+#define UNIT_TEST_
+
+#include <systemlib/err.h>
+
+
+class __EXPORT UnitTest
+{
+
+public:
+#define xstr(s) str(s)
+#define str(s) #s
+#define INLINE_GLOBAL(type,func) inline type& func() { static type x; return x; }
+
+INLINE_GLOBAL(int, mu_tests_run)
+INLINE_GLOBAL(int, mu_assertion)
+INLINE_GLOBAL(int, mu_line)
+INLINE_GLOBAL(const char*, mu_last_test)
+
+#define mu_assert(message, test) \
+ do \
+ { \
+ if (!(test)) \
+ return __FILE__ ":" xstr(__LINE__) " " message " (" #test ")"; \
+ else \
+ mu_assertion()++; \
+ } while (0)
+
+
+#define mu_run_test(test) \
+do \
+{ \
+ const char *message; \
+ mu_last_test() = #test; \
+ mu_line() = __LINE__; \
+ message = test(); \
+ mu_tests_run()++; \
+ if (message) \
+ return message; \
+} while (0)
+
+
+public:
+ UnitTest();
+ virtual ~UnitTest();
+
+ virtual const char* run_tests() = 0;
+ virtual void print_results(const char* result);
+};
+
+
+
+#endif /* UNIT_TEST_H_ */