aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/09_ardrone_flow2
-rw-r--r--ROMFS/px4fmu_common/init.d/1001_rc_quad.hil18
-rw-r--r--ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil18
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.multirotor4
-rw-r--r--makefiles/config_px4fmu-v1_default.mk4
-rw-r--r--makefiles/config_px4fmu-v1_test.mk50
-rw-r--r--makefiles/config_px4fmu-v2_default.mk4
-rw-r--r--src/drivers/drv_rc_input.h2
-rw-r--r--src/drivers/px4io/px4io.cpp10
-rw-r--r--src/drivers/stm32/drv_hrt.c39
-rw-r--r--src/lib/conversion/rotation.cpp15
-rw-r--r--src/lib/conversion/rotation.h2
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.cpp43
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.h12
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp6
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h6
-rw-r--r--src/lib/mathlib/math/Dcm.cpp174
-rw-r--r--src/lib/mathlib/math/Dcm.hpp108
-rw-r--r--src/lib/mathlib/math/EulerAngles.cpp126
-rw-r--r--src/lib/mathlib/math/EulerAngles.hpp74
-rw-r--r--src/lib/mathlib/math/Matrix.cpp193
-rw-r--r--src/lib/mathlib/math/Matrix.hpp416
-rw-r--r--src/lib/mathlib/math/Quaternion.cpp174
-rw-r--r--src/lib/mathlib/math/Quaternion.hpp124
-rw-r--r--src/lib/mathlib/math/Vector.cpp100
-rw-r--r--src/lib/mathlib/math/Vector.hpp477
-rw-r--r--src/lib/mathlib/math/Vector3.cpp99
-rw-r--r--src/lib/mathlib/math/Vector3.hpp76
-rw-r--r--src/lib/mathlib/math/arm/Matrix.cpp40
-rw-r--r--src/lib/mathlib/math/arm/Matrix.hpp292
-rw-r--r--src/lib/mathlib/math/arm/Vector.cpp40
-rw-r--r--src/lib/mathlib/math/arm/Vector.hpp236
-rw-r--r--src/lib/mathlib/math/generic/Matrix.cpp40
-rw-r--r--src/lib/mathlib/math/generic/Matrix.hpp437
-rw-r--r--src/lib/mathlib/math/generic/Vector.cpp40
-rw-r--r--src/lib/mathlib/math/generic/Vector.hpp245
-rw-r--r--src/lib/mathlib/mathlib.h8
-rw-r--r--src/lib/mathlib/module.mk17
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp113
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.hpp20
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp2
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp79
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c7
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h2
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp14
-rw-r--r--src/modules/fw_att_control_vector/ecl_fw_att_control_vector.cpp165
-rw-r--r--src/modules/fw_att_control_vector/ecl_fw_att_control_vector.h (renamed from src/lib/mathlib/math/Vector2f.cpp)122
-rw-r--r--src/modules/fw_att_control_vector/fw_att_control_vector_main.cpp744
-rw-r--r--src/modules/fw_att_control_vector/fw_att_control_vector_params.c (renamed from src/lib/mathlib/math/Vector2f.hpp)68
-rw-r--r--src/modules/fw_att_control_vector/module.mk42
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp10
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp12
-rw-r--r--src/modules/mc_att_control_vector/mc_att_control_vector_main.cpp746
-rw-r--r--src/modules/mc_att_control_vector/mc_att_control_vector_params.c20
-rw-r--r--src/modules/mc_att_control_vector/module.mk41
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp958
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_params.c25
-rw-r--r--src/modules/mc_pos_control/module.mk (renamed from src/modules/multirotor_pos_control/module.mk)9
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c4
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.c6
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c112
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.h101
-rw-r--r--src/modules/multirotor_pos_control/thrust_pid.c189
-rw-r--r--src/modules/multirotor_pos_control/thrust_pid.h76
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c582
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c55
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h34
-rw-r--r--src/modules/px4iofirmware/controls.c16
-rw-r--r--src/modules/px4iofirmware/protocol.h3
-rw-r--r--src/modules/px4iofirmware/sbus.c2
-rw-r--r--src/modules/sdlog2/sdlog2.c15
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h11
-rw-r--r--src/modules/sensors/sensors.cpp12
-rw-r--r--src/modules/systemlib/pid/pid.c106
-rw-r--r--src/modules/systemlib/pid/pid.h41
-rw-r--r--src/modules/systemlib/ppm_decode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h2
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h5
-rw-r--r--src/systemcmds/tests/module.mk1
-rw-r--r--src/systemcmds/tests/test_mathlib.cpp159
-rw-r--r--src/systemcmds/tests/tests.h1
-rw-r--r--src/systemcmds/tests/tests_main.c1
82 files changed, 4809 insertions, 3696 deletions
diff --git a/ROMFS/px4fmu_common/init.d/09_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
index 9b739f245..e4561eee3 100644
--- a/ROMFS/px4fmu_common/init.d/09_ardrone_flow
+++ b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
@@ -72,7 +72,7 @@ flow_position_estimator start
#
# Fire up the multi rotor attitude controller
#
-multirotor_att_control start
+mc_att_control_vector start
#
# Fire up the flow position controller
diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
index 9b664d63e..c15e5d7c5 100644
--- a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
+++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
@@ -60,16 +60,8 @@ hil mode_pwm
#
param set MAV_TYPE 2
-#
-# Check if we got an IO
-#
-if px4io start
-then
- echo "IO started"
-else
- fmu mode_serial
- echo "FMU started"
-fi
+fmu mode_serial
+echo "FMU started"
#
# Start the sensors (depends on orb, px4io)
@@ -79,7 +71,7 @@ sh /etc/init.d/rc.sensors
#
# Start the attitude estimator (depends on orb)
#
-att_pos_estimator_ekf start
+attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
@@ -94,12 +86,12 @@ position_estimator_inav start
#
# Start attitude control
#
-multirotor_att_control start
+mc_att_control_vector start
#
# Start position control
#
-multirotor_pos_control start
+mc_pos_control start
echo "[HIL] setup done, running"
diff --git a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
index 0cc07ad34..ad36716cf 100644
--- a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
+++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
@@ -60,16 +60,8 @@ hil mode_pwm
#
param set MAV_TYPE 2
-#
-# Check if we got an IO
-#
-if px4io start
-then
- echo "IO started"
-else
- fmu mode_serial
- echo "FMU started"
-fi
+fmu mode_serial
+echo "FMU started"
#
# Start the sensors (depends on orb, px4io)
@@ -79,7 +71,7 @@ sh /etc/init.d/rc.sensors
#
# Start the attitude estimator (depends on orb)
#
-att_pos_estimator_ekf start
+attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
@@ -94,12 +86,12 @@ position_estimator_inav start
#
# Start attitude control
#
-multirotor_att_control start
+mc_att_control_vector start
#
# Start position control
#
-multirotor_pos_control start
+mc_pos_control start
echo "[HIL] setup done, running"
diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor
index bc550ac5a..f6ac58632 100644
--- a/ROMFS/px4fmu_common/init.d/rc.multirotor
+++ b/ROMFS/px4fmu_common/init.d/rc.multirotor
@@ -31,9 +31,9 @@ position_estimator_inav start
#
# Start attitude control
#
-multirotor_att_control start
+mc_att_control_vector start
#
# Start position control
#
-multirotor_pos_control start
+mc_pos_control start
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index f724962b2..24c08b8bd 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -83,8 +83,8 @@ MODULES += examples/flow_position_estimator
#MODULES += modules/segway # XXX Needs GCC 4.7 fix
MODULES += modules/fw_pos_control_l1
MODULES += modules/fw_att_control
-MODULES += modules/multirotor_att_control
-MODULES += modules/multirotor_pos_control
+MODULES += modules/mc_att_control_vector
+MODULES += modules/mc_pos_control
MODULES += examples/flow_position_control
MODULES += examples/flow_speed_control
diff --git a/makefiles/config_px4fmu-v1_test.mk b/makefiles/config_px4fmu-v1_test.mk
new file mode 100644
index 000000000..42a35c5dd
--- /dev/null
+++ b/makefiles/config_px4fmu-v1_test.mk
@@ -0,0 +1,50 @@
+#
+# Makefile for the px4fmu_default configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test
+
+#
+# Board support modules
+#
+MODULES += drivers/device
+MODULES += drivers/stm32
+MODULES += drivers/led
+MODULES += drivers/boards/px4fmu-v1
+MODULES += systemcmds/perf
+MODULES += systemcmds/reboot
+MODULES += systemcmds/tests
+MODULES += systemcmds/nshterm
+
+#
+# Libraries
+#
+LIBRARIES += lib/mathlib/CMSIS
+MODULES += lib/mathlib
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+MODULES += modules/uORB
+MODULES += modules/systemlib/mixer
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+# command priority stack entrypoint
+BUILTIN_COMMANDS := \
+ $(call _B, sercon, , 2048, sercon_main ) \
+ $(call _B, serdis, , 2048, serdis_main )
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 3d3dd7203..f63f143c6 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -83,8 +83,8 @@ MODULES += examples/flow_position_estimator
#MODULES += modules/segway # XXX Needs GCC 4.7 fix
MODULES += modules/fw_pos_control_l1
MODULES += modules/fw_att_control
-MODULES += modules/multirotor_att_control
-MODULES += modules/multirotor_pos_control
+MODULES += modules/mc_att_control_vector
+MODULES += modules/mc_pos_control
#
# Logging
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 6f773b82a..03f1dfbe5 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -89,7 +89,7 @@ struct rc_input_values {
/** number of channels actually being seen */
uint32_t channel_count;
- /** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 1000: full reception */
+ /** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 255: full reception */
int32_t rssi;
/** Input source */
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 4e9daf910..9812ea497 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1801,6 +1801,16 @@ PX4IO::print_status()
printf(" %u", io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + i));
printf("\n");
+
+ if (raw_inputs > 0) {
+ int frame_len = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_RC_DATA);
+ printf("RC data (PPM frame len) %u us\n", frame_len);
+
+ if ((frame_len - raw_inputs * 2000 - 3000) < 0) {
+ printf("WARNING WARNING WARNING! This RC receiver does not allow safe frame detection.\n");
+ }
+ }
+
uint16_t mapped_inputs = io_reg_get(PX4IO_PAGE_RC_INPUT, PX4IO_P_RC_VALID);
printf("mapped R/C inputs 0x%04x", mapped_inputs);
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index f105251f0..5bfbe04b8 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -282,6 +282,10 @@ static void hrt_call_invoke(void);
* Note that we assume that M3 means STM32F1 (since we don't really care about the F2).
*/
# ifdef CONFIG_ARCH_CORTEXM3
+# undef GTIM_CCER_CC1NP
+# undef GTIM_CCER_CC2NP
+# undef GTIM_CCER_CC3NP
+# undef GTIM_CCER_CC4NP
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
@@ -332,10 +336,10 @@ static void hrt_call_invoke(void);
/*
* PPM decoder tuning parameters
*/
-# define PPM_MAX_PULSE_WIDTH 550 /* maximum width of a valid pulse */
+# define PPM_MAX_PULSE_WIDTH 700 /* maximum width of a valid pulse */
# define PPM_MIN_CHANNEL_VALUE 800 /* shortest valid channel signal */
# define PPM_MAX_CHANNEL_VALUE 2200 /* longest valid channel signal */
-# define PPM_MIN_START 2500 /* shortest valid start gap */
+# define PPM_MIN_START 2400 /* shortest valid start gap (only 2nd part of pulse) */
/* decoded PPM buffer */
#define PPM_MIN_CHANNELS 5
@@ -345,6 +349,7 @@ static void hrt_call_invoke(void);
#define PPM_CHANNEL_LOCK 4 /* should be less than the input timeout */
__EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS];
+__EXPORT uint16_t ppm_frame_length = 0;
__EXPORT unsigned ppm_decoded_channels = 0;
__EXPORT uint64_t ppm_last_valid_decode = 0;
@@ -362,7 +367,8 @@ static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
struct {
uint16_t last_edge; /* last capture time */
uint16_t last_mark; /* last significant edge */
- unsigned next_channel;
+ uint16_t frame_start; /* the frame width */
+ unsigned next_channel; /* next channel index */
enum {
UNSYNCH = 0,
ARM,
@@ -447,7 +453,6 @@ hrt_ppm_decode(uint32_t status)
/* how long since the last edge? - this handles counter wrapping implicitely. */
width = count - ppm.last_edge;
- ppm.last_edge = count;
ppm_edge_history[ppm_edge_next++] = width;
@@ -491,6 +496,7 @@ hrt_ppm_decode(uint32_t status)
ppm_buffer[i] = ppm_temp_buffer[i];
ppm_last_valid_decode = hrt_absolute_time();
+
}
}
@@ -500,13 +506,14 @@ hrt_ppm_decode(uint32_t status)
/* next edge is the reference for the first channel */
ppm.phase = ARM;
+ ppm.last_edge = count;
return;
}
switch (ppm.phase) {
case UNSYNCH:
/* we are waiting for a start pulse - nothing useful to do here */
- return;
+ break;
case ARM:
@@ -515,14 +522,23 @@ hrt_ppm_decode(uint32_t status)
goto error; /* pulse was too long */
/* record the mark timing, expect an inactive edge */
- ppm.last_mark = count;
- ppm.phase = INACTIVE;
- return;
+ ppm.last_mark = ppm.last_edge;
+
+ /* frame length is everything including the start gap */
+ ppm_frame_length = (uint16_t)(ppm.last_edge - ppm.frame_start);
+ ppm.frame_start = ppm.last_edge;
+ ppm.phase = ACTIVE;
+ break;
case INACTIVE:
+
+ /* we expect a short pulse */
+ if (width > PPM_MAX_PULSE_WIDTH)
+ goto error; /* pulse was too long */
+
/* this edge is not interesting, but now we are ready for the next mark */
ppm.phase = ACTIVE;
- return;
+ break;
case ACTIVE:
/* determine the interval from the last mark */
@@ -543,10 +559,13 @@ hrt_ppm_decode(uint32_t status)
ppm_temp_buffer[ppm.next_channel++] = interval;
ppm.phase = INACTIVE;
- return;
+ break;
}
+ ppm.last_edge = count;
+ return;
+
/* the state machine is corrupted; reset it */
error:
diff --git a/src/lib/conversion/rotation.cpp b/src/lib/conversion/rotation.cpp
index b078562c2..614877b18 100644
--- a/src/lib/conversion/rotation.cpp
+++ b/src/lib/conversion/rotation.cpp
@@ -41,22 +41,11 @@
#include "rotation.h"
__EXPORT void
-get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix)
+get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix)
{
- /* first set to zero */
- rot_matrix->Matrix::zero(3, 3);
-
float roll = M_DEG_TO_RAD_F * (float)rot_lookup[rot].roll;
float pitch = M_DEG_TO_RAD_F * (float)rot_lookup[rot].pitch;
float yaw = M_DEG_TO_RAD_F * (float)rot_lookup[rot].yaw;
- math::EulerAngles euler(roll, pitch, yaw);
-
- math::Dcm R(euler);
-
- for (int i = 0; i < 3; i++) {
- for (int j = 0; j < 3; j++) {
- (*rot_matrix)(i, j) = R(i, j);
- }
- }
+ rot_matrix->from_euler(roll, pitch, yaw);
}
diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h
index 85c63c0fc..0c56494c5 100644
--- a/src/lib/conversion/rotation.h
+++ b/src/lib/conversion/rotation.h
@@ -116,6 +116,6 @@ const rot_lookup_t rot_lookup[] = {
* Get the rotation matrix
*/
__EXPORT void
-get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix);
+get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix);
#endif /* ROTATION_H_ */
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
index 11def2371..3b68a0a4e 100644
--- a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
@@ -83,8 +83,8 @@ float ECL_L1_Pos_Controller::crosstrack_error(void)
return _crosstrack_error;
}
-void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, const math::Vector2f &vector_B, const math::Vector2f &vector_curr_position,
- const math::Vector2f &ground_speed_vector)
+void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector<2> &vector_A, const math::Vector<2> &vector_B, const math::Vector<2> &vector_curr_position,
+ const math::Vector<2> &ground_speed_vector)
{
/* this follows the logic presented in [1] */
@@ -94,7 +94,7 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
float ltrack_vel;
/* get the direction between the last (visited) and next waypoint */
- _target_bearing = get_bearing_to_next_waypoint(vector_curr_position.getX(), vector_curr_position.getY(), vector_B.getX(), vector_B.getY());
+ _target_bearing = get_bearing_to_next_waypoint(vector_curr_position(0), vector_curr_position(1), vector_B(0), vector_B(1));
/* enforce a minimum ground speed of 0.1 m/s to avoid singularities */
float ground_speed = math::max(ground_speed_vector.length(), 0.1f);
@@ -103,7 +103,7 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
_L1_distance = _L1_ratio * ground_speed;
/* calculate vector from A to B */
- math::Vector2f vector_AB = get_local_planar_vector(vector_A, vector_B);
+ math::Vector<2> vector_AB = get_local_planar_vector(vector_A, vector_B);
/*
* check if waypoints are on top of each other. If yes,
@@ -116,7 +116,7 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
vector_AB.normalize();
/* calculate the vector from waypoint A to the aircraft */
- math::Vector2f vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
+ math::Vector<2> vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
/* calculate crosstrack error (output only) */
_crosstrack_error = vector_AB % vector_A_to_airplane;
@@ -130,7 +130,7 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
float alongTrackDist = vector_A_to_airplane * vector_AB;
/* estimate airplane position WRT to B */
- math::Vector2f vector_B_to_P_unit = get_local_planar_vector(vector_B, vector_curr_position).normalized();
+ math::Vector<2> vector_B_to_P_unit = get_local_planar_vector(vector_B, vector_curr_position).normalized();
/* calculate angle of airplane position vector relative to line) */
@@ -143,14 +143,14 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
/* calculate eta to fly to waypoint A */
/* unit vector from waypoint A to current position */
- math::Vector2f vector_A_to_airplane_unit = vector_A_to_airplane.normalized();
+ math::Vector<2> vector_A_to_airplane_unit = vector_A_to_airplane.normalized();
/* velocity across / orthogonal to line */
xtrack_vel = ground_speed_vector % (-vector_A_to_airplane_unit);
/* velocity along line */
ltrack_vel = ground_speed_vector * (-vector_A_to_airplane_unit);
eta = atan2f(xtrack_vel, ltrack_vel);
/* bearing from current position to L1 point */
- _nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
+ _nav_bearing = atan2f(-vector_A_to_airplane_unit(1) , -vector_A_to_airplane_unit(0));
/*
* If the AB vector and the vector from B to airplane point in the same
@@ -174,7 +174,7 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
ltrack_vel = ground_speed_vector * (-vector_B_to_P_unit);
eta = atan2f(xtrack_vel, ltrack_vel);
/* bearing from current position to L1 point */
- _nav_bearing = atan2f(-vector_B_to_P_unit.getY() , -vector_B_to_P_unit.getX());
+ _nav_bearing = atan2f(-vector_B_to_P_unit(1) , -vector_B_to_P_unit(0));
} else {
@@ -194,7 +194,7 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
float eta1 = asinf(sine_eta1);
eta = eta1 + eta2;
/* bearing from current position to L1 point */
- _nav_bearing = atan2f(vector_AB.getY(), vector_AB.getX()) + eta1;
+ _nav_bearing = atan2f(vector_AB(1), vector_AB(0)) + eta1;
}
@@ -209,8 +209,8 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
_bearing_error = eta;
}
-void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector2f &vector_A, const math::Vector2f &vector_curr_position, float radius, int8_t loiter_direction,
- const math::Vector2f &ground_speed_vector)
+void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector<2> &vector_A, const math::Vector<2> &vector_curr_position, float radius, int8_t loiter_direction,
+ const math::Vector<2> &ground_speed_vector)
{
/* the complete guidance logic in this section was proposed by [2] */
@@ -220,7 +220,7 @@ void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector2f &vector_A, cons
float K_velocity = 2.0f * _L1_damping * omega;
/* update bearing to next waypoint */
- _target_bearing = get_bearing_to_next_waypoint(vector_curr_position.getX(), vector_curr_position.getY(), vector_A.getX(), vector_A.getY());
+ _target_bearing = get_bearing_to_next_waypoint(vector_curr_position(0), vector_curr_position(1), vector_A(0), vector_A(1));
/* ground speed, enforce minimum of 0.1 m/s to avoid singularities */
float ground_speed = math::max(ground_speed_vector.length() , 0.1f);
@@ -229,10 +229,10 @@ void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector2f &vector_A, cons
_L1_distance = _L1_ratio * ground_speed;
/* calculate the vector from waypoint A to current position */
- math::Vector2f vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
+ math::Vector<2> vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
/* store the normalized vector from waypoint A to current position */
- math::Vector2f vector_A_to_airplane_unit = (vector_A_to_airplane).normalized();
+ math::Vector<2> vector_A_to_airplane_unit = (vector_A_to_airplane).normalized();
/* calculate eta angle towards the loiter center */
@@ -287,19 +287,19 @@ void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector2f &vector_A, cons
/* angle between requested and current velocity vector */
_bearing_error = eta;
/* bearing from current position to L1 point */
- _nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
+ _nav_bearing = atan2f(-vector_A_to_airplane_unit(1) , -vector_A_to_airplane_unit(0));
} else {
_lateral_accel = lateral_accel_sp_circle;
_circle_mode = true;
_bearing_error = 0.0f;
/* bearing from current position to L1 point */
- _nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
+ _nav_bearing = atan2f(-vector_A_to_airplane_unit(1) , -vector_A_to_airplane_unit(0));
}
}
-void ECL_L1_Pos_Controller::navigate_heading(float navigation_heading, float current_heading, const math::Vector2f &ground_speed_vector)
+void ECL_L1_Pos_Controller::navigate_heading(float navigation_heading, float current_heading, const math::Vector<2> &ground_speed_vector)
{
/* the complete guidance logic in this section was proposed by [2] */
@@ -352,14 +352,11 @@ void ECL_L1_Pos_Controller::navigate_level_flight(float current_heading)
}
-math::Vector2f ECL_L1_Pos_Controller::get_local_planar_vector(const math::Vector2f &origin, const math::Vector2f &target) const
+math::Vector<2> ECL_L1_Pos_Controller::get_local_planar_vector(const math::Vector<2> &origin, const math::Vector<2> &target) const
{
/* this is an approximation for small angles, proposed by [2] */
- math::Vector2f out;
-
- out.setX(math::radians((target.getX() - origin.getX())));
- out.setY(math::radians((target.getY() - origin.getY())*cosf(math::radians(origin.getX()))));
+ math::Vector<2> out(math::radians((target(0) - origin(0))), math::radians((target(1) - origin(1))*cosf(math::radians(origin(0)))));
return out * static_cast<float>(CONSTANTS_RADIUS_OF_EARTH);
}
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.h b/src/lib/ecl/l1/ecl_l1_pos_controller.h
index 7a3c42a92..5c0804a39 100644
--- a/src/lib/ecl/l1/ecl_l1_pos_controller.h
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.h
@@ -160,8 +160,8 @@ public:
*
* @return sets _lateral_accel setpoint
*/
- void navigate_waypoints(const math::Vector2f &vector_A, const math::Vector2f &vector_B, const math::Vector2f &vector_curr_position,
- const math::Vector2f &ground_speed);
+ void navigate_waypoints(const math::Vector<2> &vector_A, const math::Vector<2> &vector_B, const math::Vector<2> &vector_curr_position,
+ const math::Vector<2> &ground_speed);
/**
@@ -172,8 +172,8 @@ public:
*
* @return sets _lateral_accel setpoint
*/
- void navigate_loiter(const math::Vector2f &vector_A, const math::Vector2f &vector_curr_position, float radius, int8_t loiter_direction,
- const math::Vector2f &ground_speed_vector);
+ void navigate_loiter(const math::Vector<2> &vector_A, const math::Vector<2> &vector_curr_position, float radius, int8_t loiter_direction,
+ const math::Vector<2> &ground_speed_vector);
/**
@@ -185,7 +185,7 @@ public:
*
* @return sets _lateral_accel setpoint
*/
- void navigate_heading(float navigation_heading, float current_heading, const math::Vector2f &ground_speed);
+ void navigate_heading(float navigation_heading, float current_heading, const math::Vector<2> &ground_speed);
/**
@@ -260,7 +260,7 @@ private:
* @param wp The point to convert to into the local coordinates, in WGS84 coordinates
* @return The vector in meters pointing from the reference position to the coordinates
*/
- math::Vector2f get_local_planar_vector(const math::Vector2f &origin, const math::Vector2f &target) const;
+ math::Vector<2> get_local_planar_vector(const math::Vector<2> &origin, const math::Vector<2> &target) const;
};
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index 5a56dce65..0f28bccad 100644
--- a/src/lib/external_lgpl/tecs/tecs.cpp
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -30,7 +30,7 @@ using namespace math;
*
*/
-void TECS::update_50hz(float baro_altitude, float airspeed, const math::Dcm &rotMat, const math::Vector3 &accel_body, const math::Vector3 &accel_earth)
+void TECS::update_50hz(float baro_altitude, float airspeed, const math::Matrix<3,3> &rotMat, const math::Vector<3> &accel_body, const math::Vector<3> &accel_earth)
{
// Implement third order complementary filter for height and height rate
// estimted height rate = _integ2_state
@@ -282,7 +282,7 @@ void TECS::_update_energies(void)
_SKEdot = _integ5_state * _vel_dot;
}
-void TECS::_update_throttle(float throttle_cruise, const math::Dcm &rotMat)
+void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotMat)
{
// Calculate total energy values
_STE_error = _SPE_dem - _SPE_est + _SKE_dem - _SKE_est;
@@ -505,7 +505,7 @@ void TECS::_update_STE_rate_lim(void)
_STEdot_min = - _minSinkRate * CONSTANTS_ONE_G;
}
-void TECS::update_pitch_throttle(const math::Dcm &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
+void TECS::update_pitch_throttle(const math::Matrix<3,3> &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
float throttle_min, float throttle_max, float throttle_cruise,
float pitch_limit_min, float pitch_limit_max)
{
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index 4fc009da9..d1ebacda1 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -71,10 +71,10 @@ public:
// Update of the estimated height and height rate internal state
// Update of the inertial speed rate internal state
// Should be called at 50Hz or greater
- void update_50hz(float baro_altitude, float airspeed, const math::Dcm &rotMat, const math::Vector3 &accel_body, const math::Vector3 &accel_earth);
+ void update_50hz(float baro_altitude, float airspeed, const math::Matrix<3,3> &rotMat, const math::Vector<3> &accel_body, const math::Vector<3> &accel_earth);
// Update the control loop calculations
- void update_pitch_throttle(const math::Dcm &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
+ void update_pitch_throttle(const math::Matrix<3,3> &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
float throttle_min, float throttle_max, float throttle_cruise,
float pitch_limit_min, float pitch_limit_max);
// demanded throttle in percentage
@@ -348,7 +348,7 @@ private:
void _update_energies(void);
// Update Demanded Throttle
- void _update_throttle(float throttle_cruise, const math::Dcm &rotMat);
+ void _update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotMat);
// Detect Bad Descent
void _detect_bad_descent(void);
diff --git a/src/lib/mathlib/math/Dcm.cpp b/src/lib/mathlib/math/Dcm.cpp
deleted file mode 100644
index f509f7081..000000000
--- a/src/lib/mathlib/math/Dcm.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 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[3][3]) :
- Matrix(3, 3)
-{
- Dcm &dcm = *this;
- /* set rotation matrix */
- for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
- dcm(i, j) = data[i][j];
-}
-
-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/lib/mathlib/math/Dcm.hpp b/src/lib/mathlib/math/Dcm.hpp
deleted file mode 100644
index df8970d3a..000000000
--- a/src/lib/mathlib/math/Dcm.hpp
+++ /dev/null
@@ -1,108 +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.hpp
- *
- * math direction cosine matrix
- */
-
-//#pragma once
-
-#include "Vector.hpp"
-#include "Matrix.hpp"
-
-namespace math
-{
-
-class Quaternion;
-class EulerAngles;
-
-/**
- * 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.
- */
-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);
-
- /**
- * array ctor
- */
- Dcm(const float data[3][3]);
-
- /**
- * quaternion ctor
- */
- Dcm(const Quaternion &q);
-
- /**
- * euler angles ctor
- */
- Dcm(const EulerAngles &euler);
-
- /**
- * copy ctor (deep)
- */
- Dcm(const Dcm &right);
-
- /**
- * dtor
- */
- virtual ~Dcm();
-};
-
-int __EXPORT dcmTest();
-
-} // math
-
diff --git a/src/lib/mathlib/math/EulerAngles.cpp b/src/lib/mathlib/math/EulerAngles.cpp
deleted file mode 100644
index e733d23bb..000000000
--- a/src/lib/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/lib/mathlib/math/EulerAngles.hpp b/src/lib/mathlib/math/EulerAngles.hpp
deleted file mode 100644
index 399eecfa7..000000000
--- a/src/lib/mathlib/math/EulerAngles.hpp
+++ /dev/null
@@ -1,74 +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 "Vector.hpp"
-
-namespace math
-{
-
-class Quaternion;
-class Dcm;
-
-class __EXPORT EulerAngles : public Vector
-{
-public:
- EulerAngles();
- EulerAngles(float phi, float theta, float psi);
- EulerAngles(const Quaternion &q);
- EulerAngles(const Dcm &dcm);
- virtual ~EulerAngles();
-
- // alias
- void setPhi(float phi) { (*this)(0) = phi; }
- void setTheta(float theta) { (*this)(1) = theta; }
- void setPsi(float psi) { (*this)(2) = psi; }
-
- // const accessors
- const float &getPhi() const { return (*this)(0); }
- const float &getTheta() const { return (*this)(1); }
- const float &getPsi() const { return (*this)(2); }
-
-};
-
-int __EXPORT eulerAnglesTest();
-
-} // math
-
diff --git a/src/lib/mathlib/math/Matrix.cpp b/src/lib/mathlib/math/Matrix.cpp
deleted file mode 100644
index ebd1aeda3..000000000
--- a/src/lib/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/lib/mathlib/math/Matrix.hpp b/src/lib/mathlib/math/Matrix.hpp
index f19db15ec..ea0cf4ca1 100644
--- a/src/lib/mathlib/math/Matrix.hpp
+++ b/src/lib/mathlib/math/Matrix.hpp
@@ -1,6 +1,9 @@
/****************************************************************************
*
- * 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>
+ * Pavel Kirienko <pavel.kirienko@gmail.com>
+ * 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,30 +35,401 @@
****************************************************************************/
/**
- * @file Matrix.h
+ * @file Matrix.hpp
*
- * matrix code
+ * Matrix class
*/
-#pragma once
+#ifndef MATRIX_HPP
+#define MATRIX_HPP
-#include <nuttx/config.h>
-
-#if defined(CONFIG_ARCH_CORTEXM4) && defined(CONFIG_ARCH_FPU)
-#include "arm/Matrix.hpp"
-#else
-#include "generic/Matrix.hpp"
-#endif
+#include <stdio.h>
+#include "../CMSIS/Include/arm_math.h"
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
+
+template <unsigned int M, unsigned int N>
+class __EXPORT Matrix;
+
+// MxN matrix with float elements
+template <unsigned int M, unsigned int N>
+class __EXPORT MatrixBase
+{
+public:
+ /**
+ * matrix data[row][col]
+ */
+ float data[M][N];
+
+ /**
+ * struct for using arm_math functions
+ */
+ arm_matrix_instance_f32 arm_mat;
+
+ /**
+ * trivial ctor
+ * note that this ctor will not initialize elements
+ */
+ MatrixBase() {
+ arm_mat = {M, N, &data[0][0]};
+ }
+
+ /**
+ * copyt ctor
+ */
+ MatrixBase(const MatrixBase<M, N> &m) {
+ arm_mat = {M, N, &data[0][0]};
+ memcpy(data, m.data, sizeof(data));
+ }
+
+ MatrixBase(const float *d) {
+ arm_mat = {M, N, &data[0][0]};
+ memcpy(data, d, sizeof(data));
+ }
+
+ MatrixBase(const float d[M][N]) {
+ arm_mat = {M, N, &data[0][0]};
+ memcpy(data, d, sizeof(data));
+ }
+
+ /**
+ * set data
+ */
+ void set(const float *d) {
+ memcpy(data, d, sizeof(data));
+ }
+
+ /**
+ * set data
+ */
+ void set(const float d[M][N]) {
+ memcpy(data, d, sizeof(data));
+ }
+
+ /**
+ * access by index
+ */
+ float &operator()(const unsigned int row, const unsigned int col) {
+ return data[row][col];
+ }
+
+ /**
+ * access by index
+ */
+ float operator()(const unsigned int row, const unsigned int col) const {
+ return data[row][col];
+ }
+
+ /**
+ * get rows number
+ */
+ unsigned int get_rows() const {
+ return M;
+ }
+
+ /**
+ * get columns number
+ */
+ unsigned int get_cols() const {
+ return N;
+ }
+
+ /**
+ * test for equality
+ */
+ bool operator ==(const Matrix<M, N> &m) const {
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ if (data[i][j] != m.data[i][j])
+ return false;
+
+ return true;
+ }
+
+ /**
+ * test for inequality
+ */
+ bool operator !=(const Matrix<M, N> &m) const {
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ if (data[i][j] != m.data[i][j])
+ return true;
+
+ return false;
+ }
+
+ /**
+ * set to value
+ */
+ const Matrix<M, N> &operator =(const Matrix<M, N> &m) {
+ memcpy(data, m.data, sizeof(data));
+ return *static_cast<Matrix<M, N>*>(this);
+ }
+
+ /**
+ * negation
+ */
+ Matrix<M, N> operator -(void) const {
+ Matrix<M, N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ for (unsigned int j = 0; j < M; j++)
+ res.data[i][j] = -data[i][j];
+
+ return res;
+ }
+
+ /**
+ * addition
+ */
+ Matrix<M, N> operator +(const Matrix<M, N> &m) const {
+ Matrix<M, N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ for (unsigned int j = 0; j < M; j++)
+ res.data[i][j] = data[i][j] + m.data[i][j];
+
+ return res;
+ }
+
+ Matrix<M, N> &operator +=(const Matrix<M, N> &m) {
+ for (unsigned int i = 0; i < N; i++)
+ for (unsigned int j = 0; j < M; j++)
+ data[i][j] += m.data[i][j];
+
+ return *static_cast<Matrix<M, N>*>(this);
+ }
+
+ /**
+ * subtraction
+ */
+ Matrix<M, N> operator -(const Matrix<M, N> &m) const {
+ Matrix<M, N> res;
+
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ res.data[i][j] = data[i][j] - m.data[i][j];
+
+ return res;
+ }
+
+ Matrix<M, N> &operator -=(const Matrix<M, N> &m) {
+ for (unsigned int i = 0; i < N; i++)
+ for (unsigned int j = 0; j < M; j++)
+ data[i][j] -= m.data[i][j];
+
+ return *static_cast<Matrix<M, N>*>(this);
+ }
+
+ /**
+ * uniform scaling
+ */
+ Matrix<M, N> operator *(const float num) const {
+ Matrix<M, N> res;
+
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ res.data[i][j] = data[i][j] * num;
+
+ return res;
+ }
+
+ Matrix<M, N> &operator *=(const float num) {
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ data[i][j] *= num;
+
+ return *static_cast<Matrix<M, N>*>(this);
+ }
+
+ Matrix<M, N> operator /(const float num) const {
+ Matrix<M, N> res;
+
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ res[i][j] = data[i][j] / num;
+
+ return res;
+ }
+
+ Matrix<M, N> &operator /=(const float num) {
+ for (unsigned int i = 0; i < M; i++)
+ for (unsigned int j = 0; j < N; j++)
+ data[i][j] /= num;
+
+ return *static_cast<Matrix<M, N>*>(this);
+ }
+
+ /**
+ * multiplication by another matrix
+ */
+ template <unsigned int P>
+ Matrix<M, P> operator *(const Matrix<N, P> &m) const {
+ Matrix<M, P> res;
+ arm_mat_mult_f32(&arm_mat, &m.arm_mat, &res.arm_mat);
+ return res;
+ }
+
+ /**
+ * transpose the matrix
+ */
+ Matrix<N, M> transposed(void) const {
+ Matrix<N, M> res;
+ arm_mat_trans_f32(&this->arm_mat, &res.arm_mat);
+ return res;
+ }
+
+ /**
+ * invert the matrix
+ */
+ Matrix<M, N> inversed(void) const {
+ Matrix<M, N> res;
+ arm_mat_inverse_f32(&this->arm_mat, &res.arm_mat);
+ return res;
+ }
+
+ /**
+ * set zero matrix
+ */
+ void zero(void) {
+ memset(data, 0, sizeof(data));
+ }
+
+ /**
+ * set identity matrix
+ */
+ void identity(void) {
+ memset(data, 0, sizeof(data));
+ unsigned int n = (M < N) ? M : N;
+
+ for (unsigned int i = 0; i < n; i++)
+ data[i][i] = 1;
+ }
+
+ void print(void) {
+ for (unsigned int i = 0; i < M; i++) {
+ printf("[ ");
+
+ for (unsigned int j = 0; j < N; j++)
+ printf("%.3f\t", data[i][j]);
+
+ printf(" ]\n");
+ }
+ }
+};
+
+template <unsigned int M, unsigned int N>
+class __EXPORT Matrix : public MatrixBase<M, N>
+{
+public:
+ using MatrixBase<M, N>::operator *;
+
+ Matrix() : MatrixBase<M, N>() {}
+
+ Matrix(const Matrix<M, N> &m) : MatrixBase<M, N>(m) {}
+
+ Matrix(const float *d) : MatrixBase<M, N>(d) {}
+
+ Matrix(const float d[M][N]) : MatrixBase<M, N>(d) {}
+
+ /**
+ * set to value
+ */
+ const Matrix<M, N> &operator =(const Matrix<M, N> &m) {
+ memcpy(this->data, m.data, sizeof(this->data));
+ return *this;
+ }
+
+ /**
+ * multiplication by a vector
+ */
+ Vector<M> operator *(const Vector<N> &v) const {
+ Vector<M> res;
+ arm_mat_mult_f32(&this->arm_mat, &v.arm_col, &res.arm_col);
+ return res;
+ }
+};
+
+template <>
+class __EXPORT Matrix<3, 3> : public MatrixBase<3, 3>
+{
+public:
+ using MatrixBase<3, 3>::operator *;
+
+ Matrix() : MatrixBase<3, 3>() {}
+
+ Matrix(const Matrix<3, 3> &m) : MatrixBase<3, 3>(m) {}
+
+ Matrix(const float *d) : MatrixBase<3, 3>(d) {}
+
+ Matrix(const float d[3][3]) : MatrixBase<3, 3>(d) {}
+
+ /**
+ * set to value
+ */
+ const Matrix<3, 3> &operator =(const Matrix<3, 3> &m) {
+ memcpy(this->data, m.data, sizeof(this->data));
+ return *this;
+ }
+
+ /**
+ * multiplication by a vector
+ */
+ Vector<3> operator *(const Vector<3> &v) const {
+ Vector<3> res(data[0][0] * v.data[0] + data[0][1] * v.data[1] + data[0][2] * v.data[2],
+ data[1][0] * v.data[0] + data[1][1] * v.data[1] + data[1][2] * v.data[2],
+ data[2][0] * v.data[0] + data[2][1] * v.data[1] + data[2][2] * v.data[2]);
+ return res;
+ }
+
+ /**
+ * create a rotation matrix from given euler angles
+ * based on http://gentlenav.googlecode.com/files/EulerAngles.pdf
+ */
+ void from_euler(float roll, float pitch, float yaw) {
+ float cp = cosf(pitch);
+ float sp = sinf(pitch);
+ float sr = sinf(roll);
+ float cr = cosf(roll);
+ float sy = sinf(yaw);
+ float cy = cosf(yaw);
+
+ data[0][0] = cp * cy;
+ data[0][1] = (sr * sp * cy) - (cr * sy);
+ data[0][2] = (cr * sp * cy) + (sr * sy);
+ data[1][0] = cp * sy;
+ data[1][1] = (sr * sp * sy) + (cr * cy);
+ data[1][2] = (cr * sp * sy) - (sr * cy);
+ data[2][0] = -sp;
+ data[2][1] = sr * cp;
+ data[2][2] = cr * cp;
+ }
+
+ /**
+ * get euler angles from rotation matrix
+ */
+ Vector<3> to_euler(void) const {
+ Vector<3> euler;
+ euler.data[1] = asinf(-data[2][0]);
+
+ if (fabsf(euler.data[1] - M_PI_2_F) < 1.0e-3f) {
+ euler.data[0] = 0.0f;
+ euler.data[2] = atan2f(data[1][2] - data[0][1], data[0][2] + data[1][1]) + euler.data[0];
+
+ } else if (fabsf(euler.data[1] + M_PI_2_F) < 1.0e-3f) {
+ euler.data[0] = 0.0f;
+ euler.data[2] = atan2f(data[1][2] - data[0][1], data[0][2] + data[1][1]) - euler.data[0];
+
+ } else {
+ euler.data[0] = atan2f(data[2][1], data[2][2]);
+ euler.data[2] = atan2f(data[1][0], data[0][0]);
+ }
+
+ return euler;
+ }
+};
+
+}
+
+#endif // MATRIX_HPP
diff --git a/src/lib/mathlib/math/Quaternion.cpp b/src/lib/mathlib/math/Quaternion.cpp
deleted file mode 100644
index 02fec4ca6..000000000
--- a/src/lib/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/lib/mathlib/math/Quaternion.hpp b/src/lib/mathlib/math/Quaternion.hpp
index 048a55d33..21d05c7ef 100644
--- a/src/lib/mathlib/math/Quaternion.hpp
+++ b/src/lib/mathlib/math/Quaternion.hpp
@@ -1,6 +1,9 @@
/****************************************************************************
*
- * 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>
+ * Pavel Kirienko <pavel.kirienko@gmail.com>
+ * 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
@@ -34,82 +37,129 @@
/**
* @file Quaternion.hpp
*
- * math quaternion lib
+ * Quaternion class
*/
-#pragma once
+#ifndef QUATERNION_HPP
+#define QUATERNION_HPP
+#include <math.h>
+#include "../CMSIS/Include/arm_math.h"
#include "Vector.hpp"
#include "Matrix.hpp"
namespace math
{
-class Dcm;
-class EulerAngles;
-
-class __EXPORT Quaternion : public Vector
+class __EXPORT Quaternion : public Vector<4>
{
public:
-
/**
- * default ctor
+ * trivial ctor
*/
- Quaternion();
+ Quaternion() : Vector<4>() {}
/**
- * ctor from floats
+ * copy ctor
*/
- Quaternion(float a, float b, float c, float d);
+ Quaternion(const Quaternion &q) : Vector<4>(q) {}
/**
- * ctor from data
+ * casting from vector
*/
- Quaternion(const float *data);
+ Quaternion(const Vector<4> &v) : Vector<4>(v) {}
/**
- * ctor from Vector
+ * setting ctor
*/
- Quaternion(const Vector &v);
+ Quaternion(const float d[4]) : Vector<4>(d) {}
/**
- * ctor from EulerAngles
+ * setting ctor
*/
- Quaternion(const EulerAngles &euler);
+ Quaternion(const float a0, const float b0, const float c0, const float d0): Vector<4>(a0, b0, c0, d0) {}
+
+ using Vector<4>::operator *;
/**
- * ctor from Dcm
+ * multiplication
*/
- Quaternion(const Dcm &dcm);
+ const Quaternion operator *(const Quaternion &q) const {
+ return Quaternion(
+ data[0] * q.data[0] - data[1] * q.data[1] - data[2] * q.data[2] - data[3] * q.data[3],
+ data[0] * q.data[1] + data[1] * q.data[0] + data[2] * q.data[3] - data[3] * q.data[2],
+ data[0] * q.data[2] - data[1] * q.data[3] + data[2] * q.data[0] + data[3] * q.data[1],
+ data[0] * q.data[3] + data[1] * q.data[2] - data[2] * q.data[1] + data[3] * q.data[0]);
+ }
/**
- * deep copy ctor
+ * derivative
*/
- Quaternion(const Quaternion &right);
+ const Quaternion derivative(const Vector<3> &w) {
+ float dataQ[] = {
+ data[0], -data[1], -data[2], -data[3],
+ data[1], data[0], -data[3], data[2],
+ data[2], data[3], data[0], -data[1],
+ data[3], -data[2], data[1], data[0]
+ };
+ Matrix<4, 4> Q(dataQ);
+ Vector<4> v(0.0f, w.data[0], w.data[1], w.data[2]);
+ return Q * v * 0.5f;
+ }
/**
- * dtor
+ * imaginary part of quaternion
*/
- virtual ~Quaternion();
+ Vector<3> imag(void) {
+ return Vector<3>(&data[1]);
+ }
/**
- * derivative
+ * set quaternion to rotation defined by euler angles
*/
- Vector derivative(const Vector &w);
+ void from_euler(float roll, float pitch, float yaw) {
+ double cosPhi_2 = cos(double(roll) / 2.0);
+ double sinPhi_2 = sin(double(roll) / 2.0);
+ double cosTheta_2 = cos(double(pitch) / 2.0);
+ double sinTheta_2 = sin(double(pitch) / 2.0);
+ double cosPsi_2 = cos(double(yaw) / 2.0);
+ double sinPsi_2 = sin(double(yaw) / 2.0);
+ data[0] = cosPhi_2 * cosTheta_2 * cosPsi_2 + sinPhi_2 * sinTheta_2 * sinPsi_2;
+ data[1] = sinPhi_2 * cosTheta_2 * cosPsi_2 - cosPhi_2 * sinTheta_2 * sinPsi_2;
+ data[2] = cosPhi_2 * sinTheta_2 * cosPsi_2 + sinPhi_2 * cosTheta_2 * sinPsi_2;
+ data[3] = cosPhi_2 * cosTheta_2 * sinPsi_2 - sinPhi_2 * sinTheta_2 * cosPsi_2;
+ }
+
+ void from_dcm(const Matrix<3, 3> &m) {
+ // avoiding singularities by not using division equations
+ data[0] = 0.5f * sqrtf(1.0f + m.data[0][0] + m.data[1][1] + m.data[2][2]);
+ data[1] = 0.5f * sqrtf(1.0f + m.data[0][0] - m.data[1][1] - m.data[2][2]);
+ data[2] = 0.5f * sqrtf(1.0f - m.data[0][0] + m.data[1][1] - m.data[2][2]);
+ data[3] = 0.5f * sqrtf(1.0f - m.data[0][0] - m.data[1][1] + m.data[2][2]);
+ }
/**
- * accessors
+ * create rotation matrix for the quaternion
*/
- 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); }
+ Matrix<3, 3> to_dcm(void) const {
+ Matrix<3, 3> R;
+ float aSq = data[0] * data[0];
+ float bSq = data[1] * data[1];
+ float cSq = data[2] * data[2];
+ float dSq = data[3] * data[3];
+ R.data[0][0] = aSq + bSq - cSq - dSq;
+ R.data[0][1] = 2.0f * (data[1] * data[2] - data[0] * data[3]);
+ R.data[0][2] = 2.0f * (data[0] * data[2] + data[1] * data[3]);
+ R.data[1][0] = 2.0f * (data[1] * data[2] + data[0] * data[3]);
+ R.data[1][1] = aSq - bSq + cSq - dSq;
+ R.data[1][2] = 2.0f * (data[2] * data[3] - data[0] * data[1]);
+ R.data[2][0] = 2.0f * (data[1] * data[3] - data[0] * data[2]);
+ R.data[2][1] = 2.0f * (data[0] * data[1] + data[2] * data[3]);
+ R.data[2][2] = aSq - bSq - cSq + dSq;
+ return R;
+ }
};
-int __EXPORT quaternionTest();
-} // math
+}
+#endif // QUATERNION_HPP
diff --git a/src/lib/mathlib/math/Vector.cpp b/src/lib/mathlib/math/Vector.cpp
deleted file mode 100644
index 35158a396..000000000
--- a/src/lib/mathlib/math/Vector.cpp
+++ /dev/null
@@ -1,100 +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 "Vector.hpp"
-
-namespace math
-{
-
-static const float data_testA[] = {1, 3};
-static const float data_testB[] = {4, 1};
-
-static Vector testA(2, data_testA);
-static Vector testB(2, data_testB);
-
-int __EXPORT vectorTest()
-{
- vectorAddTest();
- vectorSubTest();
- return 0;
-}
-
-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;
-}
-
-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;
-}
-
-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;
- }
-
- bool ret = true;
-
- for (size_t i = 0; i < a.getRows(); i++) {
- if (!equal(a(i), b(i), eps)) {
- printf("element mismatch (%d)\n", i);
- ret = false;
- }
- }
-
- return ret;
-}
-
-} // namespace math
diff --git a/src/lib/mathlib/math/Vector.hpp b/src/lib/mathlib/math/Vector.hpp
index 73de793d5..c7323c215 100644
--- a/src/lib/mathlib/math/Vector.hpp
+++ b/src/lib/mathlib/math/Vector.hpp
@@ -1,6 +1,9 @@
/****************************************************************************
*
- * 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>
+ * Pavel Kirienko <pavel.kirienko@gmail.com>
+ * 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,26 +35,466 @@
****************************************************************************/
/**
- * @file Vector.h
+ * @file Vector.hpp
*
- * math vector
+ * Vector class
*/
-#pragma once
+#ifndef VECTOR_HPP
+#define VECTOR_HPP
-#include <nuttx/config.h>
-
-#if defined(CONFIG_ARCH_CORTEXM4) && defined(CONFIG_ARCH_FPU)
-#include "arm/Vector.hpp"
-#else
-#include "generic/Vector.hpp"
-#endif
+#include <stdio.h>
+#include <math.h>
+#include "../CMSIS/Include/arm_math.h"
namespace math
{
-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
+
+template <unsigned int N>
+class __EXPORT Vector;
+
+template <unsigned int N>
+class __EXPORT VectorBase
+{
+public:
+ /**
+ * vector data
+ */
+ float data[N];
+
+ /**
+ * struct for using arm_math functions, represents column vector
+ */
+ arm_matrix_instance_f32 arm_col;
+
+ /**
+ * trivial ctor
+ * note that this ctor will not initialize elements
+ */
+ VectorBase() {
+ arm_col = {N, 1, &data[0]};
+ }
+
+ /**
+ * copy ctor
+ */
+ VectorBase(const VectorBase<N> &v) {
+ arm_col = {N, 1, &data[0]};
+ memcpy(data, v.data, sizeof(data));
+ }
+
+ /**
+ * setting ctor
+ */
+ VectorBase(const float d[N]) {
+ arm_col = {N, 1, &data[0]};
+ memcpy(data, d, sizeof(data));
+ }
+
+ /**
+ * set data
+ */
+ void set(const float d[N]) {
+ memcpy(data, d, sizeof(data));
+ }
+
+ /**
+ * access to elements by index
+ */
+ float &operator()(const unsigned int i) {
+ return data[i];
+ }
+
+ /**
+ * access to elements by index
+ */
+ float operator()(const unsigned int i) const {
+ return data[i];
+ }
+
+ /**
+ * get vector size
+ */
+ unsigned int get_size() const {
+ return N;
+ }
+
+ /**
+ * test for equality
+ */
+ bool operator ==(const Vector<N> &v) const {
+ for (unsigned int i = 0; i < N; i++)
+ if (data[i] != v.data[i])
+ return false;
+
+ return true;
+ }
+
+ /**
+ * test for inequality
+ */
+ bool operator !=(const Vector<N> &v) const {
+ for (unsigned int i = 0; i < N; i++)
+ if (data[i] != v.data[i])
+ return true;
+
+ return false;
+ }
+
+ /**
+ * set to value
+ */
+ const Vector<N> &operator =(const Vector<N> &v) {
+ memcpy(data, v.data, sizeof(data));
+ return *static_cast<const Vector<N>*>(this);
+ }
+
+ /**
+ * negation
+ */
+ const Vector<N> operator -(void) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = -data[i];
+
+ return res;
+ }
+
+ /**
+ * addition
+ */
+ const Vector<N> operator +(const Vector<N> &v) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = data[i] + v.data[i];
+
+ return res;
+ }
+
+ /**
+ * subtraction
+ */
+ const Vector<N> operator -(const Vector<N> &v) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = data[i] - v.data[i];
+
+ return res;
+ }
+
+ /**
+ * uniform scaling
+ */
+ const Vector<N> operator *(const float num) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = data[i] * num;
+
+ return res;
+ }
+
+ /**
+ * uniform scaling
+ */
+ const Vector<N> operator /(const float num) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = data[i] / num;
+
+ return res;
+ }
+
+ /**
+ * addition
+ */
+ const Vector<N> &operator +=(const Vector<N> &v) {
+ for (unsigned int i = 0; i < N; i++)
+ data[i] += v.data[i];
+
+ return *static_cast<const Vector<N>*>(this);
+ }
+
+ /**
+ * subtraction
+ */
+ const Vector<N> &operator -=(const Vector<N> &v) {
+ for (unsigned int i = 0; i < N; i++)
+ data[i] -= v.data[i];
+
+ return *static_cast<const Vector<N>*>(this);
+ }
+
+ /**
+ * uniform scaling
+ */
+ const Vector<N> &operator *=(const float num) {
+ for (unsigned int i = 0; i < N; i++)
+ data[i] *= num;
+
+ return *static_cast<const Vector<N>*>(this);
+ }
+
+ /**
+ * uniform scaling
+ */
+ const Vector<N> &operator /=(const float num) {
+ for (unsigned int i = 0; i < N; i++)
+ data[i] /= num;
+
+ return *static_cast<const Vector<N>*>(this);
+ }
+
+ /**
+ * dot product
+ */
+ float operator *(const Vector<N> &v) const {
+ float res = 0.0f;
+
+ for (unsigned int i = 0; i < N; i++)
+ res += data[i] * v.data[i];
+
+ return res;
+ }
+
+ /**
+ * element by element multiplication
+ */
+ const Vector<N> emult(const Vector<N> &v) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = data[i] * v.data[i];
+
+ return res;
+ }
+
+ /**
+ * element by element division
+ */
+ const Vector<N> edivide(const Vector<N> &v) const {
+ Vector<N> res;
+
+ for (unsigned int i = 0; i < N; i++)
+ res.data[i] = data[i] / v.data[i];
+
+ return res;
+ }
+
+ /**
+ * gets the length of this vector squared
+ */
+ float length_squared() const {
+ float res = 0.0f;
+
+ for (unsigned int i = 0; i < N; i++)
+ res += data[i] * data[i];
+
+ return res;
+ }
+
+ /**
+ * gets the length of this vector
+ */
+ float length() const {
+ float res = 0.0f;
+
+ for (unsigned int i = 0; i < N; i++)
+ res += data[i] * data[i];
+
+ return sqrtf(res);
+ }
+
+ /**
+ * normalizes this vector
+ */
+ void normalize() {
+ *this /= length();
+ }
+
+ /**
+ * returns the normalized version of this vector
+ */
+ Vector<N> normalized() const {
+ return *this / length();
+ }
+
+ /**
+ * set zero vector
+ */
+ void zero(void) {
+ memset(data, 0, sizeof(data));
+ }
+
+ void print(void) {
+ printf("[ ");
+
+ for (unsigned int i = 0; i < N; i++)
+ printf("%.3f\t", data[i]);
+
+ printf("]\n");
+ }
+};
+
+template <unsigned int N>
+class __EXPORT Vector : public VectorBase<N>
+{
+public:
+ Vector() : VectorBase<N>() {}
+
+ Vector(const Vector<N> &v) : VectorBase<N>(v) {}
+
+ Vector(const float d[N]) : VectorBase<N>(d) {}
+
+ /**
+ * set to value
+ */
+ const Vector<N> &operator =(const Vector<N> &v) {
+ memcpy(this->data, v.data, sizeof(this->data));
+ return *this;
+ }
+};
+
+template <>
+class __EXPORT Vector<2> : public VectorBase<2>
+{
+public:
+ Vector() : VectorBase<2>() {}
+
+ // simple copy is 1.6 times faster than memcpy
+ Vector(const Vector<2> &v) : VectorBase<2>() {
+ data[0] = v.data[0];
+ data[1] = v.data[1];
+ }
+
+ Vector(const float d[2]) : VectorBase<2>() {
+ data[0] = d[0];
+ data[1] = d[1];
+ }
+
+ Vector(const float x, const float y) : VectorBase<2>() {
+ data[0] = x;
+ data[1] = y;
+ }
+
+ /**
+ * set data
+ */
+ void set(const float d[2]) {
+ data[0] = d[0];
+ data[1] = d[1];
+ }
+
+ /**
+ * set to value
+ */
+ const Vector<2> &operator =(const Vector<2> &v) {
+ data[0] = v.data[0];
+ data[1] = v.data[1];
+ return *this;
+ }
+
+ float operator %(const Vector<2> &v) const {
+ return data[0] * v.data[1] - data[1] * v.data[0];
+ }
+};
+
+template <>
+class __EXPORT Vector<3> : public VectorBase<3>
+{
+public:
+ Vector() : VectorBase<3>() {}
+
+ // simple copy is 1.6 times faster than memcpy
+ Vector(const Vector<3> &v) : VectorBase<3>() {
+ for (unsigned int i = 0; i < 3; i++)
+ data[i] = v.data[i];
+ }
+
+ Vector(const float d[3]) : VectorBase<3>() {
+ for (unsigned int i = 0; i < 3; i++)
+ data[i] = d[i];
+ }
+
+ Vector(const float x, const float y, const float z) : VectorBase<3>() {
+ data[0] = x;
+ data[1] = y;
+ data[2] = z;
+ }
+
+ /**
+ * set data
+ */
+ void set(const float d[3]) {
+ for (unsigned int i = 0; i < 3; i++)
+ data[i] = d[i];
+ }
+
+ /**
+ * set to value
+ */
+ const Vector<3> &operator =(const Vector<3> &v) {
+ for (unsigned int i = 0; i < 3; i++)
+ data[i] = v.data[i];
+
+ return *this;
+ }
+
+ Vector<3> operator %(const Vector<3> &v) const {
+ return Vector<3>(
+ data[1] * v.data[2] - data[2] * v.data[1],
+ data[2] * v.data[0] - data[0] * v.data[2],
+ data[0] * v.data[1] - data[1] * v.data[0]
+ );
+ }
+};
+
+template <>
+class __EXPORT Vector<4> : public VectorBase<4>
+{
+public:
+ Vector() : VectorBase() {}
+
+ Vector(const Vector<4> &v) : VectorBase<4>() {
+ for (unsigned int i = 0; i < 4; i++)
+ data[i] = v.data[i];
+ }
+
+ Vector(const float d[4]) : VectorBase<4>() {
+ for (unsigned int i = 0; i < 4; i++)
+ data[i] = d[i];
+ }
+
+ Vector(const float x0, const float x1, const float x2, const float x3) : VectorBase() {
+ data[0] = x0;
+ data[1] = x1;
+ data[2] = x2;
+ data[3] = x3;
+ }
+
+ /**
+ * set data
+ */
+ void set(const float d[4]) {
+ for (unsigned int i = 0; i < 4; i++)
+ data[i] = d[i];
+ }
+
+ /**
+ * set to value
+ */
+ const Vector<4> &operator =(const Vector<4> &v) {
+ for (unsigned int i = 0; i < 4; i++)
+ data[i] = v.data[i];
+
+ return *this;
+ }
+};
+
+}
+
+#endif // VECTOR_HPP
diff --git a/src/lib/mathlib/math/Vector3.cpp b/src/lib/mathlib/math/Vector3.cpp
deleted file mode 100644
index dcb85600e..000000000
--- a/src/lib/mathlib/math/Vector3.cpp
+++ /dev/null
@@ -1,99 +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 Vector3.cpp
- *
- * math vector
- */
-
-#include "test/test.hpp"
-
-#include "Vector3.hpp"
-
-namespace math
-{
-
-Vector3::Vector3() :
- Vector(3)
-{
-}
-
-Vector3::Vector3(const Vector &right) :
- Vector(right)
-{
-#ifdef VECTOR_ASSERT
- ASSERT(right.getRows() == 3);
-#endif
-}
-
-Vector3::Vector3(float x, float y, float z) :
- Vector(3)
-{
- setX(x);
- setY(y);
- setZ(z);
-}
-
-Vector3::Vector3(const float *data) :
- Vector(3, data)
-{
-}
-
-Vector3::~Vector3()
-{
-}
-
-Vector3 Vector3::cross(const Vector3 &b) const
-{
- const 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;
-}
-
-} // namespace math
diff --git a/src/lib/mathlib/math/Vector3.hpp b/src/lib/mathlib/math/Vector3.hpp
deleted file mode 100644
index 568d9669a..000000000
--- a/src/lib/mathlib/math/Vector3.hpp
+++ /dev/null
@@ -1,76 +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 Vector3.hpp
- *
- * math 3 vector
- */
-
-#pragma once
-
-#include "Vector.hpp"
-
-namespace math
-{
-
-class __EXPORT Vector3 :
- public Vector
-{
-public:
- Vector3();
- Vector3(const Vector &right);
- Vector3(float x, float y, float z);
- Vector3(const float *data);
- virtual ~Vector3();
- Vector3 cross(const Vector3 &b) const;
-
- /**
- * 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); }
-};
-
-class __EXPORT Vector3f :
- public Vector3
-{
-};
-
-int __EXPORT vector3Test();
-} // math
-
diff --git a/src/lib/mathlib/math/arm/Matrix.cpp b/src/lib/mathlib/math/arm/Matrix.cpp
deleted file mode 100644
index 21661622a..000000000
--- a/src/lib/mathlib/math/arm/Matrix.cpp
+++ /dev/null
@@ -1,40 +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 "Matrix.hpp"
diff --git a/src/lib/mathlib/math/arm/Matrix.hpp b/src/lib/mathlib/math/arm/Matrix.hpp
deleted file mode 100644
index 1945bb02d..000000000
--- a/src/lib/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 exponent;
- float num = (*this)(i, j);
- float2SigExp(num, sig, exponent);
- printf("%6.3fe%03d ", (double)sig, exponent);
- }
-
- 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/lib/mathlib/math/arm/Vector.cpp b/src/lib/mathlib/math/arm/Vector.cpp
deleted file mode 100644
index 7ea6496bb..000000000
--- a/src/lib/mathlib/math/arm/Vector.cpp
+++ /dev/null
@@ -1,40 +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 "Vector.hpp"
diff --git a/src/lib/mathlib/math/arm/Vector.hpp b/src/lib/mathlib/math/arm/Vector.hpp
deleted file mode 100644
index 52220fc15..000000000
--- a/src/lib/mathlib/math/arm/Vector.hpp
+++ /dev/null
@@ -1,236 +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 exponent;
- float num = (*this)(i);
- float2SigExp(num, sig, exponent);
- printf("%6.3fe%03d ", (double)sig, exponent);
- }
-
- 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;
- }
- inline Vector operator-(void) const {
- Vector result(getRows());
- arm_negate_f32((float *)getData(),
- result.getData(),
- getRows());
- return result;
- }
- // other functions
- inline float dot(const Vector &right) const {
- float result = 0;
- arm_dot_prod_f32((float *)getData(),
- (float *)right.getData(),
- getRows(),
- &result);
- return result;
- }
- inline float norm() const {
- return sqrtf(dot(*this));
- }
- inline float length() const {
- return norm();
- }
- inline Vector unit() const {
- return (*this) / norm();
- }
- inline Vector normalized() const {
- return unit();
- }
- inline void normalize() {
- (*this) = (*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/lib/mathlib/math/generic/Matrix.cpp b/src/lib/mathlib/math/generic/Matrix.cpp
deleted file mode 100644
index 21661622a..000000000
--- a/src/lib/mathlib/math/generic/Matrix.cpp
+++ /dev/null
@@ -1,40 +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 "Matrix.hpp"
diff --git a/src/lib/mathlib/math/generic/Matrix.hpp b/src/lib/mathlib/math/generic/Matrix.hpp
deleted file mode 100644
index 5601a3447..000000000
--- a/src/lib/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/lib/mathlib/math/generic/Vector.cpp b/src/lib/mathlib/math/generic/Vector.cpp
deleted file mode 100644
index 7ea6496bb..000000000
--- a/src/lib/mathlib/math/generic/Vector.cpp
+++ /dev/null
@@ -1,40 +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 "Vector.hpp"
diff --git a/src/lib/mathlib/math/generic/Vector.hpp b/src/lib/mathlib/math/generic/Vector.hpp
deleted file mode 100644
index 8cfdc676d..000000000
--- a/src/lib/mathlib/math/generic/Vector.hpp
+++ /dev/null
@@ -1,245 +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;
- }
- inline Vector operator-(void) const {
- Vector result(getRows());
-
- for (size_t i = 0; i < getRows(); i++) {
- result(i) = -((*this)(i));
- }
-
- return result;
- }
- // other functions
- inline float dot(const Vector &right) const {
- float result = 0;
-
- for (size_t i = 0; i < getRows(); i++) {
- result += (*this)(i) * (*this)(i);
- }
-
- return result;
- }
- inline float norm() const {
- return sqrtf(dot(*this));
- }
- inline float length() const {
- return norm();
- }
- inline Vector unit() const {
- return (*this) / norm();
- }
- inline Vector normalized() const {
- return unit();
- }
- inline void normalize() {
- (*this) = (*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/lib/mathlib/mathlib.h b/src/lib/mathlib/mathlib.h
index 40ffb22bc..9e03855c5 100644
--- a/src/lib/mathlib/mathlib.h
+++ b/src/lib/mathlib/mathlib.h
@@ -41,13 +41,9 @@
#pragma once
-#include "math/Dcm.hpp"
-#include "math/EulerAngles.hpp"
+#include "math/Vector.hpp"
#include "math/Matrix.hpp"
#include "math/Quaternion.hpp"
-#include "math/Vector.hpp"
-#include "math/Vector3.hpp"
-#include "math/Vector2f.hpp"
#include "math/Limits.hpp"
#endif
@@ -56,4 +52,4 @@
#include "CMSIS/Include/arm_math.h"
-#endif \ No newline at end of file
+#endif
diff --git a/src/lib/mathlib/module.mk b/src/lib/mathlib/module.mk
index 72bc7db8a..191e2da73 100644
--- a/src/lib/mathlib/module.mk
+++ b/src/lib/mathlib/module.mk
@@ -35,13 +35,6 @@
# Math library
#
SRCS = math/test/test.cpp \
- math/Vector.cpp \
- math/Vector2f.cpp \
- math/Vector3.cpp \
- math/EulerAngles.cpp \
- math/Quaternion.cpp \
- math/Dcm.cpp \
- math/Matrix.cpp \
math/Limits.cpp
#
@@ -49,13 +42,3 @@ SRCS = math/test/test.cpp \
# current makefile name, since app.mk needs it.
#
APP_MAKEFILE := $(lastword $(MAKEFILE_LIST))
-
-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
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
index ecca04dd7..aca3fe7b6 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
@@ -53,21 +53,6 @@ static const int8_t ret_error = -1; // error occurred
KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
SuperBlock(parent, name),
- // ekf matrices
- F(9, 9),
- G(9, 6),
- P(9, 9),
- P0(9, 9),
- V(6, 6),
- // attitude measurement ekf matrices
- HAtt(4, 9),
- RAtt(4, 4),
- // position measurement ekf matrices
- HPos(6, 9),
- RPos(6, 6),
- // attitude representations
- C_nb(),
- q(),
// subscriptions
_sensors(&getSubscriptions(), ORB_ID(sensor_combined), 5), // limit to 200 Hz
_gps(&getSubscriptions(), ORB_ID(vehicle_gps_position), 100), // limit to 10 Hz
@@ -112,8 +97,17 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
{
using namespace math;
+ F.zero();
+ G.zero();
+ V.zero();
+ HAtt.zero();
+ RAtt.zero();
+ HPos.zero();
+ RPos.zero();
+
// initial state covariance matrix
- P0 = Matrix::identity(9) * 0.01f;
+ P0.identity();
+ P0 *= 0.01f;
P = P0;
// initial state
@@ -138,7 +132,7 @@ KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
_sensors.magnetometer_ga[2]);
// initialize dcm
- C_nb = Dcm(q);
+ C_nb = q.to_dcm();
// HPos is constant
HPos(0, 3) = 1.0f;
@@ -228,8 +222,8 @@ void KalmanNav::update()
if (correctAtt() == ret_ok) _attitudeInitCounter++;
if (_attitudeInitCounter > 100) {
- warnx("initialized EKF attitude\n");
- warnx("phi: %8.4f, theta: %8.4f, psi: %8.4f\n",
+ warnx("initialized EKF attitude");
+ warnx("phi: %8.4f, theta: %8.4f, psi: %8.4f",
double(phi), double(theta), double(psi));
_attitudeInitialized = true;
}
@@ -259,8 +253,8 @@ void KalmanNav::update()
// lat/lon and not have init
map_projection_init(lat0, lon0);
_positionInitialized = true;
- 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",
+ warnx("initialized EKF state with GPS");
+ warnx("vN: %8.4f, vE: %8.4f, vD: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f",
double(vN), double(vE), double(vD),
lat, lon, double(alt));
}
@@ -404,28 +398,28 @@ int KalmanNav::predictState(float dt)
// attitude prediction
if (_attitudeInitialized) {
- Vector3 w(_sensors.gyro_rad_s);
+ Vector<3> w(_sensors.gyro_rad_s);
// attitude
q = q + q.derivative(w) * dt;
// renormalize quaternion if needed
- if (fabsf(q.norm() - 1.0f) > 1e-4f) {
- q = q.unit();
+ if (fabsf(q.length() - 1.0f) > 1e-4f) {
+ q.normalize();
}
// C_nb update
- C_nb = Dcm(q);
+ C_nb = q.to_dcm();
// euler update
- EulerAngles euler(C_nb);
- phi = euler.getPhi();
- theta = euler.getTheta();
- psi = euler.getPsi();
+ Vector<3> euler = C_nb.to_euler();
+ phi = euler.data[0];
+ theta = euler.data[1];
+ psi = euler.data[2];
// specific acceleration in nav frame
- Vector3 accelB(_sensors.accelerometer_m_s2);
- Vector3 accelN = C_nb * accelB;
+ Vector<3> accelB(_sensors.accelerometer_m_s2);
+ Vector<3> accelN = C_nb * accelB;
fN = accelN(0);
fE = accelN(1);
fD = accelN(2);
@@ -549,10 +543,10 @@ int KalmanNav::predictStateCovariance(float dt)
G(5, 4) = C_nb(2, 1);
G(5, 5) = C_nb(2, 2);
- // continuous predictioon equations
- // for discrte time EKF
+ // continuous prediction equations
+ // for discrete time EKF
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
- P = P + (F * P + P * F.transpose() + G * V * G.transpose()) * dt;
+ P = P + (F * P + P * F.transposed() + G * V * G.transposed()) * dt;
return ret_ok;
}
@@ -577,13 +571,14 @@ int KalmanNav::correctAtt()
// 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();
+ math::Matrix<3,3> C_rp;
+ C_rp.from_euler(phi, theta, 0.0f);//C_nb.transposed();
// mag measurement
- Vector3 magBody(_sensors.magnetometer_ga);
+ Vector<3> magBody(_sensors.magnetometer_ga);
// transform to earth frame
- Vector3 magNav = C_rp * magBody;
+ Vector<3> magNav = C_rp * magBody;
// calculate error between estimate and measurement
// apply declination correction for true heading as well.
@@ -592,12 +587,12 @@ int KalmanNav::correctAtt()
if (yMag < -M_PI_F) yMag += 2*M_PI_F;
// accel measurement
- Vector3 zAccel(_sensors.accelerometer_m_s2);
- float accelMag = zAccel.norm();
- zAccel = zAccel.unit();
+ Vector<3> zAccel(_sensors.accelerometer_m_s2);
+ float accelMag = zAccel.length();
+ zAccel.normalize();
// ignore accel correction when accel mag not close to g
- Matrix RAttAdjust = RAtt;
+ Matrix<4,4> RAttAdjust = RAtt;
bool ignoreAccel = fabsf(accelMag - _g.get()) > 1.1f;
@@ -611,14 +606,10 @@ int KalmanNav::correctAtt()
}
// accel predicted measurement
- Vector3 zAccelHat = (C_nb.transpose() * Vector3(0, 0, -_g.get())).unit();
+ Vector<3> zAccelHat = (C_nb.transposed() * Vector<3>(0, 0, -_g.get())).normalized();
// 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);
+ Vector<4> y(yMag, zAccel(0) - zAccelHat(0), zAccel(1) - zAccelHat(1), zAccel(2) - zAccelHat(2));
// HMag
HAtt(0, 2) = 1;
@@ -632,17 +623,17 @@ int KalmanNav::correctAtt()
// compute correction
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
- Matrix S = HAtt * P * HAtt.transpose() + RAttAdjust; // residual covariance
- Matrix K = P * HAtt.transpose() * S.inverse();
- Vector xCorrect = K * y;
+ Matrix<4, 4> S = HAtt * P * HAtt.transposed() + RAttAdjust; // residual covariance
+ Matrix<9, 4> K = P * HAtt.transposed() * S.inversed();
+ Vector<9> xCorrect = K * y;
// check correciton is sane
- for (size_t i = 0; i < xCorrect.getRows(); i++) {
+ for (size_t i = 0; i < xCorrect.get_size(); i++) {
float val = xCorrect(i);
if (isnan(val) || isinf(val)) {
// abort correction and return
- warnx("numerical failure in att correction\n");
+ warnx("numerical failure in att correction");
// reset P matrix to P0
P = P0;
return ret_error;
@@ -669,7 +660,7 @@ int KalmanNav::correctAtt()
P = P - K * HAtt * P;
// fault detection
- float beta = y.dot(S.inverse() * y);
+ float beta = y * (S.inversed() * y);
if (beta > _faultAtt.get()) {
warnx("fault in attitude: beta = %8.4f", (double)beta);
@@ -678,7 +669,7 @@ int KalmanNav::correctAtt()
// update quaternions from euler
// angle correction
- q = Quaternion(EulerAngles(phi, theta, psi));
+ q.from_euler(phi, theta, psi);
return ret_ok;
}
@@ -688,7 +679,7 @@ int KalmanNav::correctPos()
using namespace math;
// residual
- Vector y(6);
+ Vector<6> y;
y(0) = _gps.vel_n_m_s - vN;
y(1) = _gps.vel_e_m_s - vE;
y(2) = double(_gps.lat) - double(lat) * 1.0e7 * M_RAD_TO_DEG;
@@ -698,17 +689,17 @@ int KalmanNav::correctPos()
// compute correction
// http://en.wikipedia.org/wiki/Extended_Kalman_filter
- Matrix S = HPos * P * HPos.transpose() + RPos; // residual covariance
- Matrix K = P * HPos.transpose() * S.inverse();
- Vector xCorrect = K * y;
+ Matrix<6,6> S = HPos * P * HPos.transposed() + RPos; // residual covariance
+ Matrix<9,6> K = P * HPos.transposed() * S.inversed();
+ Vector<9> xCorrect = K * y;
// check correction is sane
- for (size_t i = 0; i < xCorrect.getRows(); i++) {
+ for (size_t i = 0; i < xCorrect.get_size(); i++) {
float val = xCorrect(i);
if (!isfinite(val)) {
// abort correction and return
- warnx("numerical failure in gps correction\n");
+ warnx("numerical failure in gps correction");
// fallback to GPS
vN = _gps.vel_n_m_s;
vE = _gps.vel_e_m_s;
@@ -735,7 +726,7 @@ int KalmanNav::correctPos()
P = P - K * HPos * P;
// fault detetcion
- float beta = y.dot(S.inverse() * y);
+ float beta = y * (S.inversed() * y);
static int counter = 0;
if (beta > _faultPos.get() && (counter % 10 == 0)) {
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
index a69bde1a6..46ee4b6c8 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
@@ -125,17 +125,17 @@ public:
virtual void updateParams();
protected:
// kalman filter
- math::Matrix F; /**< Jacobian(f,x), where dx/dt = f(x,u) */
- math::Matrix G; /**< noise shaping matrix for gyro/accel */
- math::Matrix P; /**< state covariance matrix */
- math::Matrix P0; /**< initial state covariance matrix */
- math::Matrix V; /**< gyro/ accel noise matrix */
- math::Matrix HAtt; /**< attitude measurement matrix */
- math::Matrix RAtt; /**< attitude measurement noise matrix */
- math::Matrix HPos; /**< position measurement jacobian matrix */
- math::Matrix RPos; /**< position measurement noise matrix */
+ math::Matrix<9,9> F; /**< Jacobian(f,x), where dx/dt = f(x,u) */
+ math::Matrix<9,6> G; /**< noise shaping matrix for gyro/accel */
+ math::Matrix<9,9> P; /**< state covariance matrix */
+ math::Matrix<9,9> P0; /**< initial state covariance matrix */
+ math::Matrix<6,6> V; /**< gyro/ accel noise matrix */
+ math::Matrix<4,9> HAtt; /**< attitude measurement matrix */
+ math::Matrix<4,4> RAtt; /**< attitude measurement noise matrix */
+ math::Matrix<6,9> HPos; /**< position measurement jacobian matrix */
+ math::Matrix<6,6> RPos; /**< position measurement noise matrix */
// attitude
- math::Dcm C_nb; /**< direction cosine matrix from body to nav frame */
+ math::Matrix<3,3> C_nb; /**< direction cosine matrix from body to nav frame */
math::Quaternion q; /**< quaternion from body to nav frame */
// subscriptions
control::UOrbSubscription<sensor_combined_s> _sensors; /**< sensors sub. */
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 372b2d162..3d20d4d2d 100644
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -107,7 +107,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("att_pos_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 30,
- 4096,
+ 8192,
kalman_demo_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
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 a70a14fe4..36e82db43 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -58,9 +58,12 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/parameter_update.h>
#include <drivers/drv_hrt.h>
+#include <lib/mathlib/mathlib.h>
+
#include <systemlib/systemlib.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -214,6 +217,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
struct sensor_combined_s raw;
memset(&raw, 0, sizeof(raw));
+ struct vehicle_gps_position_s gps;
+ memset(&gps, 0, sizeof(gps));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_control_mode_s control_mode;
@@ -221,12 +226,18 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
uint64_t last_data = 0;
uint64_t last_measurement = 0;
+ uint64_t last_gps = 0;
+
+ float vel_prev[3] = { 0.0f, 0.0f, 0.0f };
/* 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 GPS */
+ int sub_gps = orb_subscribe(ORB_ID(vehicle_gps_position));
+
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
@@ -265,6 +276,13 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
unsigned offset_count = 0;
+ /* actual acceleration (by GPS velocity) in body frame */
+ float acc[3] = { 0.0f, 0.0f, 0.0f };
+
+ /* rotation matrix for magnetic declination */
+ math::Matrix<3, 3> R_decl;
+ R_decl.identity();
+
/* register the perf counter */
perf_counter_t ekf_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_ekf");
@@ -299,6 +317,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* update parameters */
parameters_update(&ekf_param_handles, &ekf_params);
+
+ /* update mag declination rotation matrix */
+ R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl);
}
/* only run filter if sensor values changed */
@@ -306,6 +327,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* get latest measurements */
orb_copy(ORB_ID(sensor_combined), sub_raw, &raw);
+ orb_copy(ORB_ID(vehicle_gps_position), sub_gps, &gps);
if (!initialized) {
// XXX disabling init for now
@@ -352,9 +374,43 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
sensor_last_timestamp[1] = raw.timestamp;
}
- z_k[3] = raw.accelerometer_m_s2[0];
- z_k[4] = raw.accelerometer_m_s2[1];
- z_k[5] = raw.accelerometer_m_s2[2];
+ if (gps.fix_type >= 3 && gps.eph_m < 10.0f && gps.vel_ned_valid && hrt_absolute_time() < gps.timestamp_velocity + 500000) {
+ if (last_gps != 0 && gps.timestamp_velocity != last_gps) {
+ float gps_dt = (gps.timestamp_velocity - last_gps) / 1000000.0f;
+ /* calculate acceleration in NED frame */
+ float acc_NED[3];
+ acc_NED[0] = (gps.vel_n_m_s - vel_prev[0]) / gps_dt;
+ acc_NED[1] = (gps.vel_e_m_s - vel_prev[1]) / gps_dt;
+ acc_NED[2] = (gps.vel_d_m_s - vel_prev[2]) / gps_dt;
+
+ /* project acceleration to body frame */
+ for (int i = 0; i < 3; i++) {
+ acc[i] = 0.0f;
+ for (int j = 0; j < 3; j++) {
+ acc[i] += att.R[j][i] * acc_NED[j];
+ }
+ }
+
+ vel_prev[0] = gps.vel_n_m_s;
+ vel_prev[1] = gps.vel_e_m_s;
+ vel_prev[2] = gps.vel_d_m_s;
+ }
+ last_gps = gps.timestamp_velocity;
+
+ } else {
+ acc[0] = 0.0f;
+ acc[1] = 0.0f;
+ acc[2] = 0.0f;
+
+ vel_prev[0] = 0.0f;
+ vel_prev[1] = 0.0f;
+ vel_prev[2] = 0.0f;
+ last_gps = 0;
+ }
+
+ z_k[3] = raw.accelerometer_m_s2[0] - acc[0];
+ z_k[4] = raw.accelerometer_m_s2[1] - acc[1];
+ z_k[5] = raw.accelerometer_m_s2[2] - acc[2];
/* update magnetometer measurements */
if (sensor_last_count[2] != raw.magnetometer_counter) {
@@ -425,7 +481,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- if (last_data > 0 && raw.timestamp - last_data > 12000)
+ if (last_data > 0 && raw.timestamp - last_data > 30000)
printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
last_data = raw.timestamp;
@@ -433,10 +489,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* send out */
att.timestamp = raw.timestamp;
- // XXX Apply the same transformation to the rotation matrix
- att.roll = euler[0] - ekf_params.roll_off;
- att.pitch = euler[1] - ekf_params.pitch_off;
- att.yaw = euler[2] - ekf_params.yaw_off;
+ att.roll = euler[0];
+ att.pitch = euler[1];
+ att.yaw = euler[2] + ekf_params.mag_decl;
att.rollspeed = x_aposteriori[0];
att.pitchspeed = x_aposteriori[1];
@@ -445,12 +500,16 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
att.pitchacc = x_aposteriori[4];
att.yawacc = x_aposteriori[5];
- //att.yawspeed =z_k[2] ;
/* copy offsets */
memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets));
+ /* magnetic declination */
+
+ math::Matrix<3, 3> R_body = (&Rot_matrix[0]);
+ math::Matrix<3, 3> R = R_decl * R_body;
+
/* copy rotation matrix */
- memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix));
+ memcpy(&att.R[0][0], &R.data[0][0], sizeof(att.R));
att.R_valid = true;
if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) {
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 52dac652b..a6a40b4a1 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
@@ -63,6 +63,9 @@ PARAM_DEFINE_FLOAT(ATT_ROLL_OFF3, 0.0f);
PARAM_DEFINE_FLOAT(ATT_PITCH_OFF3, 0.0f);
PARAM_DEFINE_FLOAT(ATT_YAW_OFF3, 0.0f);
+/* magnetic declination, in degrees */
+PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f);
+
int parameters_init(struct attitude_estimator_ekf_param_handles *h)
{
/* PID parameters */
@@ -81,6 +84,8 @@ int parameters_init(struct attitude_estimator_ekf_param_handles *h)
h->pitch_off = param_find("ATT_PITCH_OFF3");
h->yaw_off = param_find("ATT_YAW_OFF3");
+ h->mag_decl = param_find("ATT_MAG_DECL");
+
return OK;
}
@@ -101,5 +106,7 @@ int parameters_update(const struct attitude_estimator_ekf_param_handles *h, stru
param_get(h->pitch_off, &(p->pitch_off));
param_get(h->yaw_off, &(p->yaw_off));
+ param_get(h->mag_decl, &(p->mag_decl));
+
return OK;
}
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
index 09817d58e..b4b3ca50d 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
@@ -47,12 +47,14 @@ struct attitude_estimator_ekf_params {
float roll_off;
float pitch_off;
float yaw_off;
+ float mag_decl;
};
struct attitude_estimator_ekf_param_handles {
param_t r0, r1, r2, r3;
param_t q0, q1, q2, q3, q4;
param_t roll_off, pitch_off, yaw_off;
+ param_t mag_decl;
};
/**
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 5eeca5a1a..36b75dd58 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -194,15 +194,13 @@ int do_accel_calibration(int mavlink_fd)
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);
+ math::Matrix<3,3> board_rotation;
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;
+ math::Matrix<3,3> board_rotation_t = board_rotation.transposed();
+ math::Vector<3> accel_offs_vec(&accel_offs[0]);
+ math::Vector<3> accel_offs_rotated = board_rotation_t * accel_offs_vec;
+ math::Matrix<3,3> accel_T_mat(&accel_T[0][0]);
+ math::Matrix<3,3> 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);
diff --git a/src/modules/fw_att_control_vector/ecl_fw_att_control_vector.cpp b/src/modules/fw_att_control_vector/ecl_fw_att_control_vector.cpp
new file mode 100644
index 000000000..16e60f3e0
--- /dev/null
+++ b/src/modules/fw_att_control_vector/ecl_fw_att_control_vector.cpp
@@ -0,0 +1,165 @@
+/****************************************************************************
+ *
+ * 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 ecl_fw_att_control_vector.cpp
+ *
+ * Fixed wing attitude controller
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ *
+ */
+
+#include <mathlib/mathlib.h>
+#include <systemlib/geo/geo.h>
+#include "ecl_fw_att_control_vector.h"
+
+ECL_FWAttControlVector::ECL_FWAttControlVector() :
+ _integral_error(0.0f, 0.0f),
+ _integral_max(1000.0f, 1000.0f),
+ _rates_demanded(0.0f, 0.0f, 0.0f),
+ _k_p(1.0f, 1.0f, 1.0f),
+ _k_d(1.0f, 1.0f, 1.0f),
+ _k_i(1.0f, 1.0f, 1.0f),
+ _integral_lock(false),
+ _p_airspeed_min(12.0f),
+ _p_airspeed_max(24.0f),
+ _p_tconst(0.1f),
+ _p_roll_ffd(1.0f),
+ _airspeed_enabled(false)
+ {
+
+ }
+
+/**
+ *
+ * @param F_des_in Desired force vector in body frame (NED). Straight flight is (0 0 -1)',
+ * banking hard right (1 0 -1)' and pitching down (1 0 -1)'.
+ */
+void ECL_FWAttControlVector::control(float dt, float airspeed, float airspeed_scaling, const math::Dcm &R_nb, float roll, float pitch, float yaw, const math::Vector &F_des_in,
+ const math::Vector &angular_rates,
+ math::Vector &moment_des, float &thrust)
+{
+ if (!isfinite(airspeed) || !airspeed_enabled()) {
+ // If airspeed is not available or Inf/NaN, use the center
+ // of min / max
+ airspeed = 0.5f * (_p_airspeed_min + _p_airspeed_max);
+ }
+
+ math::Dcm R_bn(R_nb.transpose());
+ math::Matrix R_yaw_bn = math::Dcm(math::EulerAngles(0.0f, 0.0f, yaw)).transpose();
+
+ // Establish actuator signs and lift compensation
+ float lift_sign = (R_bn(3, 3) >= 0) ? 1.0f : -1.0f;
+
+ float lift_comp = CONSTANTS_ONE_G / math::max(airspeed , float(_p_airspeed_min) * (R_nb(2,3) * R_nb(2,3)) / (R_nb(3,3) * sqrtf((R_nb(2,3) * R_nb(2,3)) + (R_nb(3,3) * R_nb(3,3)))));
+ //float lift_comp = fabsf((CONSTANTS_ONE_G / math::max(airspeed , float(_p_airspeed_min)) * tanf(roll) * sinf(roll))) * _p_roll_ffd;
+
+ float cy = cosf(yaw);
+ float sy = sinf(yaw);
+
+ //math::Matrix RYaw = math::Dcm(cy,-sy,0.0f,sy,cy,0.0f,0.0f,0.0f,1.0f);
+ math::Vector z_b = math::Vector3(R_bn(0,2), R_bn(1,2), R_bn(2,2));
+
+ math::Vector3 F_des = R_yaw_bn * F_des_in;
+
+ // desired thrust in body frame
+ // avoid division by zero
+ // compensates for thrust loss due to roll/pitch
+ if (F_des(2) >= 0.1f) {
+ thrust = F_des(2) / R_bn(2, 2);
+ } else {
+ F_des(2) = 0.1f;
+ thrust= F_des(2) / R_bn(2, 2);
+ }
+
+ math::Vector3 x_B_des;
+ math::Vector3 y_B_des;
+ math::Vector3 z_B_des;
+
+ // desired body z axis
+ z_B_des = (F_des / F_des.norm());
+
+ // desired direction in world coordinates (yaw angle)
+ math::Vector3 x_C(cy, sy, 0.0f);
+ // desired body y axis
+ y_B_des = z_B_des.cross(x_C) / (z_B_des.cross(x_C)).norm();
+ // desired body x axis
+ x_B_des = y_B_des.cross(z_B_des);
+ // desired Rotation Matrix
+ math::Dcm R_des(x_B_des(0), x_B_des(1), x_B_des(2),
+ y_B_des(0), y_B_des(1), y_B_des(2),
+ z_B_des(0), z_B_des(1), z_B_des(2));
+
+
+ // Attitude Controller
+ // P controller
+
+ // error rotation matrix
+ // operation executed in quaternion space to allow large differences
+ // XXX switch between operations based on difference,
+ // benchmark both options
+ math::Quaternion e_q = math::Quaternion(R_des) - math::Quaternion(R_bn);
+ // Renormalize
+ e_q = e_q / e_q.norm();
+ math::Matrix e_R = math::Dcm(e_q);
+ //small angles: math::Matrix e_R = (R_des.transpose() * R_bn - R_bn.transpose() * R_des) * 0.5f;
+
+ // error rotation vector
+ math::Vector e_R_v(3);
+ e_R_v(0) = e_R(1,2);
+ e_R_v(1) = e_R(0,2);
+ e_R_v(2) = e_R(0,1);
+
+
+ // attitude integral error
+ math::Vector intError = math::Vector3(0.0f, 0.0f, 0.0f);
+ if (!_integral_lock) {
+
+ if (fabsf(_integral_error(0)) < _integral_max(0)) {
+ _integral_error(0) = _integral_error(0) + e_R_v(0) * dt;
+ }
+
+ if (fabsf(_integral_error(1)) < _integral_max(1)) {
+ _integral_error(1) = _integral_error(1) + e_R_v(1) * dt;
+ }
+
+ intError(0) = _integral_error(0);
+ intError(1) = _integral_error(1);
+ intError(2) = 0.0f;
+ }
+
+ _rates_demanded = (e_R_v * _k_p(0) + angular_rates * _k_d(0) + intError * _k_i(0));
+ moment_des = _rates_demanded;
+}
diff --git a/src/lib/mathlib/math/Vector2f.cpp b/src/modules/fw_att_control_vector/ecl_fw_att_control_vector.h
index 68e741817..40e4662a3 100644
--- a/src/lib/mathlib/math/Vector2f.cpp
+++ b/src/modules/fw_att_control_vector/ecl_fw_att_control_vector.h
@@ -32,72 +32,84 @@
****************************************************************************/
/**
- * @file Vector2f.cpp
+ * @file ecl_fw_att_control_vector.cpp
+ *
+ * Fixed wing attitude controller
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
*
- * math vector
*/
-#include "test/test.hpp"
+#include <mathlib/mathlib.h>
+
+class ECL_FWAttControlVector {
+
+public:
+ ECL_FWAttControlVector();
+ void control(float dt, float airspeed, float airspeed_scaling, const math::Dcm &R_nb, float roll, float pitch, float yaw, const math::Vector &F_des_in,
+ const math::Vector &angular_rates,
+ math::Vector &moment_des, float &thrust);
-#include "Vector2f.hpp"
+ void set_imax(float integral_max) {
+ _integral_max(0) = integral_max;
+ _integral_max(1) = integral_max;
+ }
-namespace math
-{
+ void set_tconst(float tconst) {
+ _p_tconst = tconst;
+ }
-Vector2f::Vector2f() :
- Vector(2)
-{
-}
+ void set_k_p(float roll, float pitch, float yaw) {
+ _k_p(0) = roll;
+ _k_p(1) = pitch;
+ _k_p(2) = yaw;
+ }
-Vector2f::Vector2f(const Vector &right) :
- Vector(right)
-{
-#ifdef VECTOR_ASSERT
- ASSERT(right.getRows() == 2);
-#endif
-}
+ void set_k_d(float roll, float pitch, float yaw) {
+ _k_d(0) = roll;
+ _k_d(1) = pitch;
+ _k_d(2) = yaw;
+ }
-Vector2f::Vector2f(float x, float y) :
- Vector(2)
-{
- setX(x);
- setY(y);
-}
+ void set_k_i(float roll, float pitch, float yaw) {
+ _k_i(0) = roll;
+ _k_i(1) = pitch;
+ _k_i(2) = yaw;
+ }
-Vector2f::Vector2f(const float *data) :
- Vector(2, data)
-{
-}
+ void reset_integral() {
+ _integral_error(0) = 0.0f;
+ _integral_error(1) = 0.0f;
+ }
-Vector2f::~Vector2f()
-{
-}
+ void lock_integral(bool lock) {
+ _integral_lock = lock;
+ }
-float Vector2f::cross(const Vector2f &b) const
-{
- const Vector2f &a = *this;
- return a(0)*b(1) - a(1)*b(0);
-}
+ bool airspeed_enabled() {
+ return _airspeed_enabled;
+ }
-float Vector2f::operator %(const Vector2f &v) const
-{
- return cross(v);
-}
-
-float Vector2f::operator *(const Vector2f &v) const
-{
- return dot(v);
-}
+ void enable_airspeed(bool airspeed) {
+ _airspeed_enabled = airspeed;
+ }
-int __EXPORT vector2fTest()
-{
- printf("Test Vector2f\t\t: ");
- // test float ctor
- Vector2f v(1, 2);
- ASSERT(equal(v(0), 1));
- ASSERT(equal(v(1), 2));
- printf("PASS\n");
- return 0;
-}
+ math::Vector3 get_rates_des() {
+ return _rates_demanded;
+ }
-} // namespace math
+protected:
+ math::Vector2f _integral_error;
+ math::Vector2f _integral_max;
+ math::Vector3 _rates_demanded;
+ math::Vector3 _k_p;
+ math::Vector3 _k_d;
+ math::Vector3 _k_i;
+ bool _integral_lock;
+ float _p_airspeed_min;
+ float _p_airspeed_max;
+ float _p_tconst;
+ float _p_roll_ffd;
+ bool _airspeed_enabled;
+};
diff --git a/src/modules/fw_att_control_vector/fw_att_control_vector_main.cpp b/src/modules/fw_att_control_vector/fw_att_control_vector_main.cpp
new file mode 100644
index 000000000..c64f82e54
--- /dev/null
+++ b/src/modules/fw_att_control_vector/fw_att_control_vector_main.cpp
@@ -0,0 +1,744 @@
+/****************************************************************************
+ *
+ * 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_vector_main.c
+ * Implementation of a generic attitude controller based on classic orthogonal PIDs.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Please refer to the library files for the authors and acknowledgements of
+ * the used control library functions.
+ */
+
+#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_status.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+
+#include "ecl_fw_att_control_vector.h"
+
+/**
+ * Fixedwing attitude control app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int fw_att_control_vector_main(int argc, char *argv[]);
+
+class FixedwingAttitudeControlVector
+{
+public:
+ /**
+ * Constructor
+ */
+ FixedwingAttitudeControlVector();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~FixedwingAttitudeControlVector();
+
+ /**
+ * 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 _vstatus_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_control_sub; /**< notification of manual control updates */
+ int _arming_sub; /**< arming status of outputs */
+
+ orb_advert_t _rate_sp_pub; /**< rate setpoint publication */
+ 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_status_s _vstatus; /**< vehicle status */
+ struct actuator_controls_s _actuators; /**< actuator control inputs */
+ struct actuator_armed_s _arming; /**< actuator arming status */
+
+ 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_up;
+ float p_rmax_dn;
+ float p_imax;
+ float p_rll;
+ float r_p;
+ float r_d;
+ float r_i;
+ float r_imax;
+ float r_rmax;
+ float y_slip;
+ float y_int;
+ float y_damp;
+ float y_rll;
+ float y_imax;
+
+ 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_up;
+ param_t p_rmax_dn;
+ param_t p_imax;
+ param_t p_rll;
+ param_t r_p;
+ param_t r_d;
+ param_t r_i;
+ param_t r_imax;
+ param_t r_rmax;
+ param_t y_slip;
+ param_t y_int;
+ param_t y_damp;
+ param_t y_rll;
+ param_t y_imax;
+
+ param_t airspeed_min;
+ param_t airspeed_trim;
+ param_t airspeed_max;
+ } _parameter_handles; /**< handles for interesting parameters */
+
+
+ ECL_FWAttControlVector _att_control;
+
+
+ /**
+ * 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 airspeed updates.
+ */
+ bool vehicle_airspeed_poll();
+
+ /**
+ * Check for accel updates.
+ */
+ void vehicle_accel_poll();
+
+ /**
+ * Check for set triplet updates.
+ */
+ void vehicle_setpoint_poll();
+
+ /**
+ * Check for arming status updates.
+ */
+ void arming_status_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;
+
+FixedwingAttitudeControlVector *g_control;
+}
+
+FixedwingAttitudeControlVector::FixedwingAttitudeControlVector() :
+
+ _task_should_exit(false),
+ _control_task(-1),
+
+/* subscriptions */
+ _att_sub(-1),
+ _accel_sub(-1),
+ _airspeed_sub(-1),
+ _vstatus_sub(-1),
+ _params_sub(-1),
+ _manual_control_sub(-1),
+ _arming_sub(-1),
+
+/* publications */
+ _rate_sp_pub(-1),
+ _actuators_0_pub(-1),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
+/* states */
+ _setpoint_valid(false),
+ _airspeed_valid(false)
+{
+ // _parameter_handles.roll_p = param_find("FW_ROLL_P");
+ // _parameter_handles.pitch_p = param_find("FW_PITCH_P");
+ _parameter_handles.tconst = param_find("FW_TCONST");
+ _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_up = param_find("FW_P_RMAX_UP");
+ _parameter_handles.p_rmax_dn = param_find("FW_P_RMAX_DN");
+ _parameter_handles.p_imax = param_find("FW_P_IMAX");
+ _parameter_handles.p_rll = param_find("FW_P_RLL");
+
+ _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_imax = param_find("FW_R_IMAX");
+ _parameter_handles.r_rmax = param_find("FW_R_RMAX");
+
+ _parameter_handles.y_slip = param_find("FW_Y_SLIP");
+ _parameter_handles.y_int = param_find("FW_Y_INT");
+ _parameter_handles.y_damp = param_find("FW_Y_DAMP");
+ _parameter_handles.y_rll = param_find("FW_Y_RLL");
+ _parameter_handles.y_imax = 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();
+}
+
+FixedwingAttitudeControlVector::~FixedwingAttitudeControlVector()
+{
+ 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
+FixedwingAttitudeControlVector::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_up, &(_parameters.p_rmax_up));
+ param_get(_parameter_handles.p_rmax_dn, &(_parameters.p_rmax_dn));
+ param_get(_parameter_handles.p_imax, &(_parameters.p_imax));
+ param_get(_parameter_handles.p_rll, &(_parameters.p_rll));
+
+ 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_imax, &(_parameters.r_imax));
+ param_get(_parameter_handles.r_rmax, &(_parameters.r_rmax));
+
+ param_get(_parameter_handles.y_slip, &(_parameters.y_slip));
+ param_get(_parameter_handles.y_int, &(_parameters.y_int));
+ param_get(_parameter_handles.y_damp, &(_parameters.y_damp));
+ param_get(_parameter_handles.y_rll, &(_parameters.y_rll));
+ param_get(_parameter_handles.y_imax, &(_parameters.y_imax));
+
+ 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 */
+ _att_control.set_tconst(_parameters.tconst);
+ _att_control.set_k_p(math::radians(_parameters.r_p),
+ math::radians(_parameters.p_p), 0.0f);
+ _att_control.set_k_d(math::radians(_parameters.r_p),
+ math::radians(_parameters.p_p), 0.0f);
+ _att_control.set_k_i(math::radians(_parameters.r_i),
+ math::radians(_parameters.p_i),
+ math::radians(_parameters.y_int));
+
+ return OK;
+}
+
+void
+FixedwingAttitudeControlVector::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);
+ }
+}
+
+bool
+FixedwingAttitudeControlVector::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
+FixedwingAttitudeControlVector::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
+FixedwingAttitudeControlVector::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
+FixedwingAttitudeControlVector::arming_status_poll()
+{
+ /* check if there is a new setpoint */
+ bool arming_updated;
+ orb_check(_arming_sub, &arming_updated);
+
+ if (arming_updated) {
+ orb_copy(ORB_ID(actuator_armed), _arming_sub, &_arming);
+ }
+}
+
+void
+FixedwingAttitudeControlVector::task_main_trampoline(int argc, char *argv[])
+{
+ att_control::g_control->task_main();
+}
+
+void
+FixedwingAttitudeControlVector::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));
+ _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));
+ _arming_sub = orb_subscribe(ORB_ID(actuator_armed));
+
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_vstatus_sub, 200);
+ orb_set_interval(_att_sub, 100);
+
+ parameters_update();
+
+ /* initialize values of critical structs until first regular update */
+ _arming.armed = false;
+
+ /* get an initial update for all sensor and status data */
+ (void)vehicle_airspeed_poll();
+ vehicle_setpoint_poll();
+ vehicle_accel_poll();
+ vehicle_status_poll();
+ arming_status_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();
+
+ /* check vehicle status for changes to publication state */
+ vehicle_status_poll();
+
+ /* check for arming status changes */
+ arming_status_poll();
+
+ /* lock integrator until armed */
+ bool lock_integrator;
+ if (_arming.armed) {
+ lock_integrator = false;
+ } else {
+ lock_integrator = true;
+ }
+
+ /* decide if in stabilized or full manual control */
+
+ if (_vstatus.state_machine == SYSTEM_STATE_MANUAL && !(_vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS)
+ ) {
+
+ _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;
+
+ } else if (_vstatus.state_machine == SYSTEM_STATE_AUTO ||
+ (_vstatus.state_machine == SYSTEM_STATE_STABILIZED) ||
+ (_vstatus.state_machine == SYSTEM_STATE_MANUAL && _vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS)) {
+
+ /* 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;
+
+ float roll_sp, pitch_sp;
+ float throttle_sp = 0.0f;
+
+ if (_vstatus.state_machine == SYSTEM_STATE_AUTO) {
+ roll_sp = _att_sp.roll_body;
+ pitch_sp = _att_sp.pitch_body;
+ throttle_sp = _att_sp.thrust;
+ } else if ((_vstatus.state_machine == SYSTEM_STATE_STABILIZED) ||
+ (_vstatus.state_machine == SYSTEM_STATE_MANUAL && _vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS)) {
+
+ /*
+ * 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;
+ }
+
+ math::Dcm R_nb(_att.R);
+
+ // Transform body frame forces to
+ // global frame
+ const math::Vector3 F_des(pitch_sp, roll_sp, throttle_sp);
+ const math::Vector3 angular_rates(_att.rollspeed, _att.pitchspeed, _att.yawspeed);
+
+ // Return variables
+ math::Vector3 moments_des;
+ float thrust;
+
+ _att_control.control(deltaT, airspeed_scaling, airspeed, R_nb, _att.roll, _att.pitch, _att.yaw,
+ F_des, angular_rates, moments_des, thrust);
+
+ _actuators.control[0] = (isfinite(moments_des(0))) ? moments_des(0) * actuator_scaling : 0.0f;
+ _actuators.control[1] = (isfinite(moments_des(1))) ? moments_des(1) * actuator_scaling : 0.0f;
+ _actuators.control[2] = 0.0f;//(isfinite(moments_des(0))) ? moments_des(0) * actuator_scaling : 0.0f;
+
+ /* throttle passed through */
+ _actuators.control[3] = (isfinite(thrust)) ? thrust : 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;
+ math::Vector3 rates_des = _att_control.get_rates_des();
+ rates_sp.roll = rates_des(0);
+ rates_sp.pitch = rates_des(1);
+ rates_sp.yaw = 0.0f; // XXX rates_des(2);
+
+ rates_sp.timestamp = hrt_absolute_time();
+
+ if (_rate_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _actuators_0_pub, &rates_sp);
+
+ } else {
+ /* advertise and publish */
+ _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
+ }
+
+ /* 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
+FixedwingAttitudeControlVector::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)&FixedwingAttitudeControlVector::task_main_trampoline,
+ nullptr);
+
+ if (_control_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int fw_att_control_vector_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 FixedwingAttitudeControlVector;
+
+ 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/lib/mathlib/math/Vector2f.hpp b/src/modules/fw_att_control_vector/fw_att_control_vector_params.c
index ecd62e81c..7e434c164 100644
--- a/src/lib/mathlib/math/Vector2f.hpp
+++ b/src/modules/fw_att_control_vector/fw_att_control_vector_params.c
@@ -1,6 +1,7 @@
/****************************************************************************
*
* 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
@@ -17,7 +18,7 @@
* 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
+ * 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,
@@ -32,48 +33,35 @@
****************************************************************************/
/**
- * @file Vector2f.hpp
+ * @file fw_pos_control_l1_params.c
*
- * math 3 vector
+ * Parameters defined by the L1 position control task
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
-#pragma once
-
-#include "Vector.hpp"
-
-namespace math
-{
+#include <nuttx/config.h>
-class __EXPORT Vector2f :
- public Vector
-{
-public:
- Vector2f();
- Vector2f(const Vector &right);
- Vector2f(float x, float y);
- Vector2f(const float *data);
- virtual ~Vector2f();
- float cross(const Vector2f &b) const;
- float operator %(const Vector2f &v) const;
- float operator *(const Vector2f &v) const;
- inline Vector2f operator*(const float &right) const {
- return Vector::operator*(right);
- }
+#include <systemlib/param/param.h>
- /**
- * accessors
- */
- void setX(float x) { (*this)(0) = x; }
- void setY(float y) { (*this)(1) = y; }
- const float &getX() const { return (*this)(0); }
- const float &getY() const { return (*this)(1); }
-};
-
-class __EXPORT Vector2 :
- public Vector2f
-{
-};
-
-int __EXPORT vector2fTest();
-} // math
+/*
+ * Controller parameters, accessible via MAVLink
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_TCONST, 0.5f);
+PARAM_DEFINE_FLOAT(FW_P_P, 40.0f);
+PARAM_DEFINE_FLOAT(FW_P_D, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_RMAX_UP, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_RMAX_DN, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_P_RLL, 1.0f);
+PARAM_DEFINE_FLOAT(FW_R_P, 40.0f);
+PARAM_DEFINE_FLOAT(FW_R_D, 0.0f);
+PARAM_DEFINE_FLOAT(FW_R_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_R_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_R_RMAX, 60);
+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_vector/module.mk b/src/modules/fw_att_control_vector/module.mk
new file mode 100644
index 000000000..e78a71595
--- /dev/null
+++ b/src/modules/fw_att_control_vector/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Multirotor attitude controller (vector based, no Euler singularities)
+#
+
+MODULE_COMMAND = fw_att_control_vector
+
+SRCS = fw_att_control_vector_main.cpp \
+ ecl_fw_att_control_vector.cpp \
+ fw_att_control_vector_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
index 3784337ac..40cb05b7d 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -182,7 +182,7 @@ private:
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
+ math::Matrix<3, 3> _R_nb; ///< current attitude
ECL_L1_Pos_Controller _l1_control;
TECS _tecs;
@@ -743,8 +743,8 @@ FixedwingPositionControl::control_position(const math::Vector2f &current_positio
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;
+ math::Vector<3> accel_body(_accel.x, _accel.y, _accel.z);
+ math::Vector<3> accel_earth = _R_nb.transposed() * accel_body;
_tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
float altitude_error = _mission_item_triplet.current.altitude - _global_pos.alt;
@@ -1205,8 +1205,8 @@ FixedwingPositionControl::task_main()
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);
+ math::Vector<2> ground_speed(_global_pos.vx, _global_pos.vy);
+ math::Vector<2> current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
/*
* Attempt to control position, on success (= sensors present and not in manual mode),
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 7b6fad658..f8694ef28 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -579,6 +579,7 @@ handle_message(mavlink_message_t *msg)
hil_gps.alt = gps.alt;
hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
+ hil_gps.timestamp_variance = gps.time_usec;
hil_gps.s_variance_m_s = 5.0f;
hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
@@ -590,6 +591,7 @@ handle_message(mavlink_message_t *msg)
if (heading_rad > M_PI_F)
heading_rad -= 2.0f * M_PI_F;
+ hil_gps.timestamp_velocity = gps.time_usec;
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
@@ -683,8 +685,8 @@ handle_message(mavlink_message_t *msg)
/* Calculate Rotation Matrix */
math::Quaternion q(hil_state.attitude_quaternion);
- math::Dcm C_nb(q);
- math::EulerAngles euler(C_nb);
+ math::Matrix<3,3> C_nb = q.to_dcm();
+ math::Vector<3> euler = C_nb.to_euler();
/* set rotation matrix */
for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
@@ -699,9 +701,9 @@ handle_message(mavlink_message_t *msg)
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.roll = euler(0);
+ hil_attitude.pitch = euler(1);
+ hil_attitude.yaw = euler(2);
hil_attitude.rollspeed = hil_state.rollspeed;
hil_attitude.pitchspeed = hil_state.pitchspeed;
hil_attitude.yawspeed = hil_state.yawspeed;
diff --git a/src/modules/mc_att_control_vector/mc_att_control_vector_main.cpp b/src/modules/mc_att_control_vector/mc_att_control_vector_main.cpp
new file mode 100644
index 000000000..ef6a46810
--- /dev/null
+++ b/src/modules/mc_att_control_vector/mc_att_control_vector_main.cpp
@@ -0,0 +1,746 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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>
+ *
+ * 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 mc_att_control_vector_main.c
+ * Implementation of a multicopter attitude controller based on desired rotation matrix.
+ *
+ * References
+ * [1] Daniel Mellinger and Vijay Kumar, "Minimum Snap Trajectory Generation and Control for Quadrotors",
+ * http://www.seas.upenn.edu/~dmel/mellingerICRA11.pdf
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
+ */
+
+#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/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/actuator_armed.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+#include <lib/geo/geo.h>
+
+/**
+ * Multicopter attitude control app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int mc_att_control_vector_main(int argc, char *argv[]);
+
+#define MIN_TAKEOFF_THROTTLE 0.3f
+#define YAW_DEADZONE 0.01f
+
+class MulticopterAttitudeControl
+{
+public:
+ /**
+ * Constructor
+ */
+ MulticopterAttitudeControl();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~MulticopterAttitudeControl();
+
+ /**
+ * 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 _att_sp_sub; /**< vehicle attitude setpoint */
+ int _control_mode_sub; /**< vehicle control mode subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_sub; /**< notification of manual control updates */
+ int _arming_sub; /**< arming status of outputs */
+
+ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
+ orb_advert_t _rates_sp_pub; /**< rate setpoint publication */
+ orb_advert_t _actuators_0_pub; /**< actuator control group 0 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 vehicle_control_mode_s _control_mode; /**< vehicle control mode */
+ struct actuator_controls_s _actuators; /**< actuator control inputs */
+ struct actuator_armed_s _arming; /**< actuator arming status */
+ struct vehicle_rates_setpoint_s _rates_sp; /**< vehicle rates setpoint */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ math::Matrix<3, 3> _K; /**< diagonal gain matrix for position error */
+ math::Matrix<3, 3> _K_rate_p; /**< diagonal gain matrix for angular rate error */
+ math::Matrix<3, 3> _K_rate_d; /**< diagonal gain matrix for angular rate derivative */
+
+ math::Vector<3> _rates_prev; /**< angular rates on previous step */
+
+ struct {
+ param_t att_p;
+ param_t att_rate_p;
+ param_t att_rate_d;
+ param_t yaw_p;
+ param_t yaw_rate_p;
+ param_t yaw_rate_d;
+ } _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 control mode.
+ */
+ void vehicle_control_mode_poll();
+
+ /**
+ * Check for changes in manual inputs.
+ */
+ void vehicle_manual_poll();
+
+ /**
+ * Check for set triplet updates.
+ */
+ void vehicle_setpoint_poll();
+
+ /**
+ * Check for arming status updates.
+ */
+ void arming_status_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;
+
+MulticopterAttitudeControl *g_control;
+}
+
+MulticopterAttitudeControl::MulticopterAttitudeControl() :
+
+ _task_should_exit(false),
+ _control_task(-1),
+
+/* subscriptions */
+ _att_sub(-1),
+ _att_sp_sub(-1),
+ _control_mode_sub(-1),
+ _params_sub(-1),
+ _manual_sub(-1),
+ _arming_sub(-1),
+
+/* publications */
+ _att_sp_pub(-1),
+ _rates_sp_pub(-1),
+ _actuators_0_pub(-1),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "fw att control"))
+
+{
+ memset(&_att, 0, sizeof(_att));
+ memset(&_att_sp, 0, sizeof(_att_sp));
+ memset(&_manual, 0, sizeof(_manual));
+ memset(&_control_mode, 0, sizeof(_control_mode));
+ memset(&_arming, 0, sizeof(_arming));
+
+ _K.zero();
+ _K_rate_p.zero();
+ _K_rate_d.zero();
+
+ _rates_prev.zero();
+
+ _parameter_handles.att_p = param_find("MC_ATT_P");
+ _parameter_handles.att_rate_p = param_find("MC_ATTRATE_P");
+ _parameter_handles.att_rate_d = param_find("MC_ATTRATE_D");
+ _parameter_handles.yaw_p = param_find("MC_YAWPOS_P");
+ _parameter_handles.yaw_rate_p = param_find("MC_YAWRATE_P");
+ _parameter_handles.yaw_rate_d = param_find("MC_YAWRATE_D");
+
+ /* fetch initial parameter values */
+ parameters_update();
+}
+
+MulticopterAttitudeControl::~MulticopterAttitudeControl()
+{
+ 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
+MulticopterAttitudeControl::parameters_update()
+{
+ float att_p;
+ float att_rate_p;
+ float att_rate_d;
+ float yaw_p;
+ float yaw_rate_p;
+ float yaw_rate_d;
+
+ param_get(_parameter_handles.att_p, &att_p);
+ param_get(_parameter_handles.att_rate_p, &att_rate_p);
+ param_get(_parameter_handles.att_rate_d, &att_rate_d);
+ param_get(_parameter_handles.yaw_p, &yaw_p);
+ param_get(_parameter_handles.yaw_rate_p, &yaw_rate_p);
+ param_get(_parameter_handles.yaw_rate_d, &yaw_rate_d);
+
+ _K(0, 0) = att_p;
+ _K(1, 1) = att_p;
+ _K(2, 2) = yaw_p;
+
+ _K_rate_p(0, 0) = att_rate_p;
+ _K_rate_p(1, 1) = att_rate_p;
+ _K_rate_p(2, 2) = yaw_rate_p;
+
+ _K_rate_d(0, 0) = att_rate_d;
+ _K_rate_d(1, 1) = att_rate_d;
+ _K_rate_d(2, 2) = yaw_rate_d;
+
+ return OK;
+}
+
+void
+MulticopterAttitudeControl::vehicle_control_mode_poll()
+{
+ bool control_mode_updated;
+
+ /* Check HIL state if vehicle status has changed */
+ orb_check(_control_mode_sub, &control_mode_updated);
+
+ if (control_mode_updated) {
+
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+ }
+}
+
+void
+MulticopterAttitudeControl::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);
+ }
+}
+
+void
+MulticopterAttitudeControl::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);
+ }
+}
+
+void
+MulticopterAttitudeControl::arming_status_poll()
+{
+ /* check if there is a new setpoint */
+ bool arming_updated;
+ orb_check(_arming_sub, &arming_updated);
+
+ if (arming_updated) {
+ orb_copy(ORB_ID(actuator_armed), _arming_sub, &_arming);
+ }
+}
+
+void
+MulticopterAttitudeControl::task_main_trampoline(int argc, char *argv[])
+{
+ att_control::g_control->task_main();
+}
+
+void
+MulticopterAttitudeControl::task_main()
+{
+ /* inform about start */
+ warnx("started");
+ fflush(stdout);
+
+ /*
+ * do subscriptions
+ */
+ _att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ _control_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));
+ _arming_sub = orb_subscribe(ORB_ID(actuator_armed));
+
+ /* rate limit attitude updates to 100Hz */
+ orb_set_interval(_att_sub, 10);
+
+ parameters_update();
+
+ /* initialize values of critical structs until first regular update */
+ _arming.armed = false;
+
+ /* get an initial update for all sensor and status data */
+ vehicle_setpoint_poll();
+ vehicle_control_mode_poll();
+ vehicle_manual_poll();
+ arming_status_poll();
+
+ /* setpoint rotation matrix */
+ math::Matrix<3, 3> R_sp;
+ R_sp.identity();
+
+ /* rotation matrix for current state */
+ math::Matrix<3, 3> R;
+ R.identity();
+
+ /* current angular rates */
+ math::Vector<3> rates;
+ rates.zero();
+
+ /* identity matrix */
+ math::Matrix<3, 3> I;
+ I.identity();
+
+ math::Quaternion q;
+
+ bool reset_yaw_sp = true;
+
+ /* 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) {
+ /* copy the topic to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+
+ parameters_update();
+ }
+
+ /* only run controller if attitude changed */
+ if (fds[1].revents & POLLIN) {
+ static uint64_t last_run = 0;
+ float dt = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+ /* guard against too large dt's */
+ if (dt > 0.02f)
+ dt = 0.02f;
+
+ /* copy attitude topic */
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+
+ vehicle_setpoint_poll();
+ vehicle_control_mode_poll();
+ arming_status_poll();
+ vehicle_manual_poll();
+
+ float yaw_sp_move_rate = 0.0f;
+ bool publish_att_sp = false;
+
+ /* define which input is the dominating control input */
+ if (_control_mode.flag_control_manual_enabled) {
+ /* manual input */
+ if (!_control_mode.flag_control_climb_rate_enabled) {
+ /* pass throttle directly if not in altitude control mode */
+ _att_sp.thrust = _manual.throttle;
+ }
+
+ if (!_arming.armed) {
+ /* reset yaw setpoint when disarmed */
+ reset_yaw_sp = true;
+ }
+
+ if (_control_mode.flag_control_attitude_enabled) {
+ /* control attitude, update attitude setpoint depending on mode */
+
+ if (_att_sp.thrust < 0.1f) {
+ // TODO
+ //if (_status.condition_landed) {
+ /* reset yaw setpoint if on ground */
+ // reset_yaw_sp = true;
+ //}
+ } else {
+ if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) {
+ /* move yaw setpoint */
+ yaw_sp_move_rate = _manual.yaw;
+ _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt);
+ _att_sp.R_valid = false;
+ publish_att_sp = true;
+ }
+ }
+
+ /* reset yaw setpint to current position if needed */
+ if (reset_yaw_sp) {
+ reset_yaw_sp = false;
+ _att_sp.yaw_body = _att.yaw;
+ _att_sp.R_valid = false;
+ publish_att_sp = 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;
+ _att_sp.R_valid = false;
+ publish_att_sp = true;
+ }
+
+ } else {
+ /* manual rate inputs (ACRO) */
+ // TODO
+ /* reset yaw setpoint after ACRO */
+ reset_yaw_sp = true;
+ }
+
+ } 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;
+ publish_att_sp = true;
+ }
+ }
+
+ /* reset yaw setpoint after non-manual control */
+ reset_yaw_sp = true;
+ }
+
+ if (_att_sp.R_valid) {
+ /* rotation matrix in _att_sp is valid, use it */
+ R_sp.set(&_att_sp.R_body[0][0]);
+ } else {
+ /* rotation matrix in _att_sp is not valid, use euler angles instead */
+ R_sp.from_euler(_att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body);
+
+ /* copy rotation matrix back to setpoint struct */
+ memcpy(&_att_sp.R_body[0][0], &R_sp.data[0][0], sizeof(_att_sp.R_body));
+ _att_sp.R_valid = true;
+ }
+
+ if (publish_att_sp) {
+ /* publish the attitude setpoint */
+ _att_sp.timestamp = hrt_absolute_time();
+
+ if (_att_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp);
+
+ } else {
+ _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
+ }
+ }
+
+ /* rotation matrix for current state */
+ R.set(_att.R);
+
+ /* current body angular rates */
+ rates(0) = _att.rollspeed;
+ rates(1) = _att.pitchspeed;
+ rates(2) = _att.yawspeed;
+
+ /* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */
+ math::Vector<3> R_z(R(0, 2), R(1, 2), R(2, 2));
+ math::Vector<3> R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2));
+
+ /* axis and sin(angle) of desired rotation */
+ math::Vector<3> e_R = R.transposed() * (R_z % R_sp_z);
+
+ /* calculate angle error */
+ float e_R_z_sin = e_R.length();
+ float e_R_z_cos = R_z * R_sp_z;
+
+ /* calculate weight for yaw control */
+ float yaw_w = R_sp(2, 2) * R_sp(2, 2);
+
+ /* calculate rotation matrix after roll/pitch only rotation */
+ math::Matrix<3, 3> R_rp;
+
+ if (e_R_z_sin > 0.0f) {
+ /* get axis-angle representation */
+ float e_R_z_angle = atan2f(e_R_z_sin, e_R_z_cos);
+ math::Vector<3> e_R_z_axis = e_R / e_R_z_sin;
+
+ e_R = e_R_z_axis * e_R_z_angle;
+
+ /* cross product matrix for e_R_axis */
+ math::Matrix<3, 3> e_R_cp;
+ e_R_cp.zero();
+ e_R_cp(0, 1) = -e_R_z_axis(2);
+ e_R_cp(0, 2) = e_R_z_axis(1);
+ e_R_cp(1, 0) = e_R_z_axis(2);
+ e_R_cp(1, 2) = -e_R_z_axis(0);
+ e_R_cp(2, 0) = -e_R_z_axis(1);
+ e_R_cp(2, 1) = e_R_z_axis(0);
+
+ /* rotation matrix for roll/pitch only rotation */
+ R_rp = R * (I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos));
+
+ } else {
+ /* zero roll/pitch rotation */
+ R_rp = R;
+ }
+
+ /* R_rp and R_sp has the same Z axis, calculate yaw error */
+ math::Vector<3> R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0));
+ math::Vector<3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0));
+ e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w;
+
+ if (e_R_z_cos < 0.0f) {
+ /* for large thrust vector rotations use another rotation method:
+ * calculate angle and axis for R -> R_sp rotation directly */
+ q.from_dcm(R.transposed() * R_sp);
+ math::Vector<3> e_R_d = q.imag();
+ e_R_d.normalize();
+ e_R_d *= 2.0f * atan2f(e_R_d.length(), q(0));
+
+ /* use fusion of Z axis based rotation and direct rotation */
+ float direct_w = e_R_z_cos * e_R_z_cos * yaw_w;
+ e_R = e_R * (1.0f - direct_w) + e_R_d * direct_w;
+ }
+
+ /* angular rates setpoint*/
+ math::Vector<3> rates_sp = _K * e_R;
+
+ /* feed forward yaw setpoint rate */
+ rates_sp(2) += yaw_sp_move_rate * yaw_w;
+ math::Vector<3> control = _K_rate_p * (rates_sp - rates) + _K_rate_d * (_rates_prev - rates) / fmaxf(dt, 0.003f);
+ _rates_prev = rates;
+
+ /* publish the attitude rates setpoint */
+ _rates_sp.roll = rates_sp(0);
+ _rates_sp.pitch = rates_sp(1);
+ _rates_sp.yaw = rates_sp(2);
+ _rates_sp.thrust = _att_sp.thrust;
+ _rates_sp.timestamp = hrt_absolute_time();
+
+ if (_rates_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &_rates_sp);
+
+ } else {
+ _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_rates_sp);
+ }
+
+ /* publish the attitude controls */
+ _actuators.control[0] = (isfinite(control(0))) ? control(0) : 0.0f;
+ _actuators.control[1] = (isfinite(control(1))) ? control(1) : 0.0f;
+ _actuators.control[2] = (isfinite(control(2))) ? control(2) : 0.0f;
+ _actuators.control[3] = (isfinite(_rates_sp.thrust)) ? _rates_sp.thrust : 0.0f;
+ _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("exit");
+
+ _control_task = -1;
+ _exit(0);
+}
+
+int
+MulticopterAttitudeControl::start()
+{
+ ASSERT(_control_task == -1);
+
+ /* start the task */
+ _control_task = task_spawn_cmd("mc_att_control_vector",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&MulticopterAttitudeControl::task_main_trampoline,
+ nullptr);
+
+ if (_control_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int mc_att_control_vector_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: mc_att_control_vector {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (att_control::g_control != nullptr)
+ errx(1, "already running");
+
+ att_control::g_control = new MulticopterAttitudeControl;
+
+ 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/mc_att_control_vector/mc_att_control_vector_params.c b/src/modules/mc_att_control_vector/mc_att_control_vector_params.c
new file mode 100644
index 000000000..613d1945b
--- /dev/null
+++ b/src/modules/mc_att_control_vector/mc_att_control_vector_params.c
@@ -0,0 +1,20 @@
+/*
+ * mc_att_control_vector_params.c
+ *
+ * Created on: 26.12.2013
+ * Author: ton
+ */
+
+#include <systemlib/param/param.h>
+
+/* multicopter attitude controller parameters */
+PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 2.0f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.0f);
+PARAM_DEFINE_FLOAT(MC_ATT_P, 6.0f);
+PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
+PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.1f);
+PARAM_DEFINE_FLOAT(MC_ATTRATE_D, 0.002f);
+PARAM_DEFINE_FLOAT(MC_ATTRATE_I, 0.0f);
diff --git a/src/modules/mc_att_control_vector/module.mk b/src/modules/mc_att_control_vector/module.mk
new file mode 100644
index 000000000..de0675df8
--- /dev/null
+++ b/src/modules/mc_att_control_vector/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Multirotor attitude controller (vector based, no Euler singularities)
+#
+
+MODULE_COMMAND = mc_att_control_vector
+
+SRCS = mc_att_control_vector_main.cpp \
+ mc_att_control_vector_params.c
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
new file mode 100644
index 000000000..948459c43
--- /dev/null
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -0,0 +1,958 @@
+/****************************************************************************
+ *
+ * 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 mc_pos_control_main.cpp
+ *
+ * Multirotor position controller.
+ */
+
+#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/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/actuator_armed.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/vehicle_global_position_setpoint.h>
+#include <uORB/topics/vehicle_global_velocity_setpoint.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <systemlib/pid/pid.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+#include <lib/geo/geo.h>
+#include <mavlink/mavlink_log.h>
+
+#define TILT_COS_MAX 0.7f
+#define SIGMA 0.000001f
+
+/**
+ * Multicopter position control app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int mc_pos_control_main(int argc, char *argv[]);
+
+class MulticopterPositionControl
+{
+public:
+ /**
+ * Constructor
+ */
+ MulticopterPositionControl();
+
+ /**
+ * Destructor, also kills task.
+ */
+ ~MulticopterPositionControl();
+
+ /**
+ * Start task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+private:
+
+ bool _task_should_exit; /**< if true, task should exit */
+ int _control_task; /**< task handle for task */
+
+ int _att_sub; /**< vehicle attitude subscription */
+ int _att_sp_sub; /**< vehicle attitude setpoint */
+ int _control_mode_sub; /**< vehicle control mode subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_sub; /**< notification of manual control updates */
+ int _arming_sub; /**< arming status of outputs */
+ int _local_pos_sub; /**< vehicle local position */
+ int _global_pos_sp_sub; /**< vehicle global position setpoint */
+
+ orb_advert_t _local_pos_sp_pub; /**< local position setpoint publication */
+ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
+ orb_advert_t _global_vel_sp_pub; /**< vehicle global velocity 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 vehicle_control_mode_s _control_mode; /**< vehicle control mode */
+ struct actuator_armed_s _arming; /**< actuator arming status */
+ struct vehicle_local_position_s _local_pos; /**< vehicle local position */
+ struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position */
+ struct vehicle_global_position_setpoint_s _global_pos_sp; /**< vehicle global position setpoint */
+ struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */
+
+ struct {
+ param_t takeoff_alt;
+ param_t takeoff_gap;
+ param_t thr_min;
+ param_t thr_max;
+ param_t z_p;
+ param_t z_vel_p;
+ param_t z_vel_i;
+ param_t z_vel_d;
+ param_t z_vel_max;
+ param_t z_ff;
+ param_t xy_p;
+ param_t xy_vel_p;
+ param_t xy_vel_i;
+ param_t xy_vel_d;
+ param_t xy_vel_max;
+ param_t xy_ff;
+ param_t tilt_max;
+
+ param_t rc_scale_pitch;
+ param_t rc_scale_roll;
+ param_t rc_scale_yaw;
+ } _params_handles; /**< handles for interesting parameters */
+
+ struct {
+ float takeoff_alt;
+ float takeoff_gap;
+ float thr_min;
+ float thr_max;
+ float tilt_max;
+
+ float rc_scale_pitch;
+ float rc_scale_roll;
+ float rc_scale_yaw;
+
+ math::Vector<3> pos_p;
+ math::Vector<3> vel_p;
+ math::Vector<3> vel_i;
+ math::Vector<3> vel_d;
+ math::Vector<3> vel_ff;
+ math::Vector<3> vel_max;
+ math::Vector<3> sp_offs_max;
+ } _params;
+
+ math::Vector<3> _pos;
+ math::Vector<3> _vel;
+ math::Vector<3> _pos_sp;
+ math::Vector<3> _vel_sp;
+ math::Vector<3> _vel_prev; /**< velocity on previous step */
+
+ /**
+ * Update our local parameter cache.
+ */
+ int parameters_update(bool force);
+
+ /**
+ * Update control outputs
+ */
+ void control_update();
+
+ /**
+ * Check for changes in subscribed topics.
+ */
+ void poll_subscriptions();
+
+ static float scale_control(float ctl, float end, float dz);
+
+ /**
+ * 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 pos_control
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+MulticopterPositionControl *g_control;
+}
+
+MulticopterPositionControl::MulticopterPositionControl() :
+
+ _task_should_exit(false),
+ _control_task(-1),
+
+/* subscriptions */
+ _att_sub(-1),
+ _att_sp_sub(-1),
+ _control_mode_sub(-1),
+ _params_sub(-1),
+ _manual_sub(-1),
+ _arming_sub(-1),
+ _local_pos_sub(-1),
+ _global_pos_sp_sub(-1),
+
+/* publications */
+ _local_pos_sp_pub(-1),
+ _att_sp_pub(-1),
+ _global_vel_sp_pub(-1)
+{
+ memset(&_att, 0, sizeof(_att));
+ memset(&_att_sp, 0, sizeof(_att_sp));
+ memset(&_manual, 0, sizeof(_manual));
+ memset(&_control_mode, 0, sizeof(_control_mode));
+ memset(&_arming, 0, sizeof(_arming));
+ memset(&_local_pos, 0, sizeof(_local_pos));
+ memset(&_local_pos_sp, 0, sizeof(_local_pos_sp));
+ memset(&_global_pos_sp, 0, sizeof(_global_pos_sp));
+ memset(&_global_vel_sp, 0, sizeof(_global_vel_sp));
+
+ _params.pos_p.zero();
+ _params.vel_p.zero();
+ _params.vel_i.zero();
+ _params.vel_d.zero();
+ _params.vel_max.zero();
+ _params.vel_ff.zero();
+ _params.sp_offs_max.zero();
+
+ _pos.zero();
+ _vel.zero();
+ _pos_sp.zero();
+ _vel_sp.zero();
+ _vel_prev.zero();
+
+ _params_handles.takeoff_alt = param_find("NAV_TAKEOFF_ALT");
+ _params_handles.takeoff_gap = param_find("NAV_TAKEOFF_GAP");
+ _params_handles.thr_min = param_find("MPC_THR_MIN");
+ _params_handles.thr_max = param_find("MPC_THR_MAX");
+ _params_handles.z_p = param_find("MPC_Z_P");
+ _params_handles.z_vel_p = param_find("MPC_Z_VEL_P");
+ _params_handles.z_vel_i = param_find("MPC_Z_VEL_I");
+ _params_handles.z_vel_d = param_find("MPC_Z_VEL_D");
+ _params_handles.z_vel_max = param_find("MPC_Z_VEL_MAX");
+ _params_handles.z_ff = param_find("MPC_Z_FF");
+ _params_handles.xy_p = param_find("MPC_XY_P");
+ _params_handles.xy_vel_p = param_find("MPC_XY_VEL_P");
+ _params_handles.xy_vel_i = param_find("MPC_XY_VEL_I");
+ _params_handles.xy_vel_d = param_find("MPC_XY_VEL_D");
+ _params_handles.xy_vel_max = param_find("MPC_XY_VEL_MAX");
+ _params_handles.xy_ff = param_find("MPC_XY_FF");
+ _params_handles.tilt_max = param_find("MPC_TILT_MAX");
+ _params_handles.rc_scale_pitch = param_find("RC_SCALE_PITCH");
+ _params_handles.rc_scale_roll = param_find("RC_SCALE_ROLL");
+ _params_handles.rc_scale_yaw = param_find("RC_SCALE_YAW");
+
+ /* fetch initial parameter values */
+ parameters_update(true);
+}
+
+MulticopterPositionControl::~MulticopterPositionControl()
+{
+ 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);
+ }
+
+ pos_control::g_control = nullptr;
+}
+
+int
+MulticopterPositionControl::parameters_update(bool force)
+{
+ bool updated;
+ struct parameter_update_s param_upd;
+
+ orb_check(_params_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(parameter_update), _params_sub, &param_upd);
+
+ if (updated || force) {
+ param_get(_params_handles.takeoff_alt, &_params.takeoff_alt);
+ param_get(_params_handles.takeoff_gap, &_params.takeoff_gap);
+ param_get(_params_handles.thr_min, &_params.thr_min);
+ param_get(_params_handles.thr_max, &_params.thr_max);
+ param_get(_params_handles.tilt_max, &_params.tilt_max);
+ param_get(_params_handles.rc_scale_pitch, &_params.rc_scale_pitch);
+ param_get(_params_handles.rc_scale_roll, &_params.rc_scale_roll);
+ param_get(_params_handles.rc_scale_yaw, &_params.rc_scale_yaw);
+
+ float v;
+ param_get(_params_handles.xy_p, &v);
+ _params.pos_p(0) = v;
+ _params.pos_p(1) = v;
+ param_get(_params_handles.z_p, &v);
+ _params.pos_p(2) = v;
+ param_get(_params_handles.xy_vel_p, &v);
+ _params.vel_p(0) = v;
+ _params.vel_p(1) = v;
+ param_get(_params_handles.z_vel_p, &v);
+ _params.vel_p(2) = v;
+ param_get(_params_handles.xy_vel_i, &v);
+ _params.vel_i(0) = v;
+ _params.vel_i(1) = v;
+ param_get(_params_handles.z_vel_i, &v);
+ _params.vel_i(2) = v;
+ param_get(_params_handles.xy_vel_d, &v);
+ _params.vel_d(0) = v;
+ _params.vel_d(1) = v;
+ param_get(_params_handles.z_vel_d, &v);
+ _params.vel_d(2) = v;
+ param_get(_params_handles.xy_vel_max, &v);
+ _params.vel_max(0) = v;
+ _params.vel_max(1) = v;
+ param_get(_params_handles.z_vel_max, &v);
+ _params.vel_max(2) = v;
+ param_get(_params_handles.xy_ff, &v);
+ _params.vel_ff(0) = v;
+ _params.vel_ff(1) = v;
+ param_get(_params_handles.z_ff, &v);
+ _params.vel_ff(2) = v;
+
+ _params.sp_offs_max = _params.vel_max.edivide(_params.pos_p) * 2.0f;
+ }
+
+ return OK;
+}
+
+void
+MulticopterPositionControl::poll_subscriptions()
+{
+ bool updated;
+
+ orb_check(_att_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+
+ orb_check(_att_sp_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), _att_sp_sub, &_att_sp);
+
+ orb_check(_control_mode_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+
+ orb_check(_manual_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(manual_control_setpoint), _manual_sub, &_manual);
+
+ orb_check(_arming_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(actuator_armed), _arming_sub, &_arming);
+
+ orb_check(_global_pos_sp_sub, &updated);
+ if (updated)
+ orb_copy(ORB_ID(vehicle_global_position_setpoint), _global_pos_sp_sub, &_global_pos_sp);
+}
+
+float
+MulticopterPositionControl::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;
+ }
+}
+
+void
+MulticopterPositionControl::task_main_trampoline(int argc, char *argv[])
+{
+ pos_control::g_control->task_main();
+}
+
+void
+MulticopterPositionControl::task_main()
+{
+ warnx("started");
+
+ static int mavlink_fd;
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(mavlink_fd, "[mpc] started");
+
+ /*
+ * do subscriptions
+ */
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ _att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ _control_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));
+ _arming_sub = orb_subscribe(ORB_ID(actuator_armed));
+ _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
+ _global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
+
+ parameters_update(true);
+
+ /* initialize values of critical structs until first regular update */
+ _arming.armed = false;
+
+ /* get an initial update for all sensor and status data */
+ poll_subscriptions();
+
+ 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;
+ hrt_abstime local_ref_timestamp = 0;
+
+ math::Vector<3> sp_move_rate;
+ sp_move_rate.zero();
+ math::Vector<3> thrust_int;
+ thrust_int.zero();
+ math::Matrix<3, 3> R;
+ R.identity();
+
+ /* wakeup source */
+ struct pollfd fds[1];
+
+ /* Setup of loop */
+ fds[0].fd = _local_pos_sub;
+ fds[0].events = POLLIN;
+
+ while (!_task_should_exit) {
+ /* wait for up to 500ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 500);
+
+ /* timed out - periodic check for _task_should_exit */
+ if (pret == 0)
+ continue;
+
+ /* this is undesirable but not much we can do */
+ if (pret < 0) {
+ warn("poll error %d, %d", pret, errno);
+ continue;
+ }
+
+ orb_copy(ORB_ID(vehicle_local_position), _local_pos_sub, &_local_pos);
+
+ poll_subscriptions();
+ parameters_update(false);
+
+ hrt_abstime t = hrt_absolute_time();
+ float dt = t_prev != 0 ? (t - t_prev) * 0.000001f : 0.0f;
+ t_prev = t;
+
+ 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;
+
+ if (_control_mode.flag_control_altitude_enabled ||
+ _control_mode.flag_control_position_enabled ||
+ _control_mode.flag_control_climb_rate_enabled ||
+ _control_mode.flag_control_velocity_enabled) {
+
+ _pos(0) = _local_pos.x;
+ _pos(1) = _local_pos.y;
+ _pos(2) = _local_pos.z;
+ _vel(0) = _local_pos.vx;
+ _vel(1) = _local_pos.vy;
+ _vel(2) = _local_pos.vz;
+
+ sp_move_rate.zero();
+
+ 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 */
+ _pos_sp(2) += _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;
+ _pos_sp(2) = _pos(2);
+ mavlink_log_info(mavlink_fd, "[mpc] reset alt sp: %.2f", (double) - _pos_sp(2));
+ }
+
+ /* move altitude setpoint with throttle stick */
+ sp_move_rate(2) = -scale_control(_manual.throttle - 0.5f, 0.5f, alt_ctl_dz);
+ }
+
+ if (_control_mode.flag_control_position_enabled) {
+ if (reset_man_sp_xy) {
+ reset_man_sp_xy = false;
+ _pos_sp(0) = _pos(0);
+ _pos_sp(1) = _pos(1);
+ mavlink_log_info(mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1));
+ }
+
+ /* move position setpoint with roll/pitch stick */
+ sp_move_rate(0) = scale_control(-_manual.pitch / _params.rc_scale_pitch, 1.0f, pos_ctl_dz);
+ sp_move_rate(1) = scale_control(_manual.roll / _params.rc_scale_roll, 1.0f, pos_ctl_dz);
+ }
+
+ /* limit setpoint move rate */
+ float sp_move_norm = sp_move_rate.length();
+ if (sp_move_norm > 1.0f) {
+ sp_move_rate /= sp_move_norm;
+ }
+
+ /* scale to max speed and rotate around yaw */
+ math::Matrix<3, 3> R_yaw_sp;
+ R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
+ sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
+
+ /* move position setpoint */
+ _pos_sp += sp_move_rate * dt;
+
+ /* check if position setpoint is too far from actual position */
+ math::Vector<3> pos_sp_offs = (_pos_sp - _pos).edivide(_params.vel_max);
+ float pos_sp_offs_norm = pos_sp_offs.length();
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.vel_max);
+ }
+
+ /* 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 {
+ // TODO AUTO
+ _pos_sp = _pos;
+ }
+
+ _local_pos_sp.x = _pos_sp(0);
+ _local_pos_sp.y = _pos_sp(1);
+ _local_pos_sp.z = _pos_sp(2);
+
+ /* publish local position setpoint */
+ if (_local_pos_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &_local_pos_sp);
+
+ } else {
+ _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp);
+ }
+
+ /* run position & altitude controllers, calculate velocity setpoint */
+ math::Vector<3> pos_err = _pos_sp - _pos;
+ _vel_sp = pos_err.emult(_params.pos_p) + sp_move_rate.emult(_params.vel_ff);
+
+ if (!_control_mode.flag_control_altitude_enabled) {
+ reset_man_sp_z = true;
+ _vel_sp(2) = 0.0f;
+ }
+
+ if (!_control_mode.flag_control_position_enabled) {
+ reset_man_sp_xy = true;
+ _vel_sp(0) = 0.0f;
+ _vel_sp(1) = 0.0f;
+ }
+
+ if (!_control_mode.flag_control_manual_enabled) {
+ /* limit 3D speed only in AUTO mode */
+ float vel_sp_norm = _vel_sp.edivide(_params.vel_max).length();
+
+ if (vel_sp_norm > 1.0f) {
+ _vel_sp /= vel_sp_norm;
+ }
+ }
+
+ _global_vel_sp.vx = _vel_sp(0);
+ _global_vel_sp.vy = _vel_sp(1);
+ _global_vel_sp.vz = _vel_sp(2);
+
+ /* publish velocity setpoint */
+ if (_global_vel_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &_global_vel_sp);
+
+ } else {
+ _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp);
+ }
+
+ if (_control_mode.flag_control_climb_rate_enabled || _control_mode.flag_control_velocity_enabled) {
+ /* reset integrals if needed */
+ 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_int(2) = -i;
+ mavlink_log_info(mavlink_fd, "[mpc] reset hovering thrust: %.2f", (double)i);
+ }
+ } else {
+ reset_int_z = true;
+ }
+
+ if (_control_mode.flag_control_velocity_enabled) {
+ if (reset_int_xy) {
+ reset_int_xy = false;
+ thrust_int(0) = 0.0f;
+ thrust_int(1) = 0.0f;
+ mavlink_log_info(mavlink_fd, "[mpc] reset xy vel integral");
+ }
+ } else {
+ reset_int_xy = true;
+ }
+
+ /* velocity error */
+ math::Vector<3> vel_err = _vel_sp - _vel;
+
+ /* derivative of velocity error, not includes setpoint acceleration */
+ math::Vector<3> vel_err_d = (sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt;
+ _vel_prev = _vel;
+
+ /* thrust vector in NED frame */
+ math::Vector<3> thrust_sp = vel_err.emult(_params.vel_p) + vel_err_d.emult(_params.vel_d) + thrust_int;
+
+ if (!_control_mode.flag_control_velocity_enabled) {
+ thrust_sp(0) = 0.0f;
+ thrust_sp(1) = 0.0f;
+ }
+ if (!_control_mode.flag_control_climb_rate_enabled) {
+ thrust_sp(2) = 0.0f;
+ }
+
+ /* limit thrust vector and check for saturation */
+ bool saturation_xy = false;
+ bool saturation_z = false;
+
+ /* limit min lift */
+ float thr_min = _params.thr_min;
+ if (!_control_mode.flag_control_velocity_enabled && thr_min < 0.0f) {
+ /* don't allow downside thrust direction in manual attitude mode */
+ thr_min = 0.0f;
+ }
+
+ if (-thrust_sp(2) < thr_min) {
+ thrust_sp(2) = -thr_min;
+ saturation_z = true;
+ }
+
+ /* limit max tilt */
+ float tilt = atan2f(math::Vector<2>(thrust_sp(0), thrust_sp(1)).length(), -thrust_sp(2));
+
+ if (tilt > _params.tilt_max && _params.thr_min >= 0.0f) {
+ /* crop horizontal component */
+ float k = tanf(_params.tilt_max) / tanf(tilt);
+ thrust_sp(0) *= k;
+ thrust_sp(1) *= k;
+ saturation_xy = true;
+ }
+
+ /* limit max thrust */
+ float thrust_abs = thrust_sp.length();
+
+ if (thrust_abs > _params.thr_max) {
+ if (thrust_sp(2) < 0.0f) {
+ if (-thrust_sp(2) > _params.thr_max) {
+ /* thrust Z component is too large, limit it */
+ thrust_sp(0) = 0.0f;
+ thrust_sp(1) = 0.0f;
+ thrust_sp(2) = -_params.thr_max;
+ saturation_xy = true;
+ saturation_z = true;
+
+ } else {
+ /* preserve thrust Z component and lower XY, keeping altitude is more important than position */
+ float thrust_xy_max = sqrtf(_params.thr_max * _params.thr_max - thrust_sp(2) * thrust_sp(2));
+ float thrust_xy_abs = math::Vector<2>(thrust_sp(0), thrust_sp(1)).length();
+ float k = thrust_xy_max / thrust_xy_abs;
+ thrust_sp(0) *= k;
+ thrust_sp(1) *= k;
+ saturation_xy = true;
+ }
+
+ } else {
+ /* Z component is negative, going down, simply limit thrust vector */
+ float k = _params.thr_max / thrust_abs;
+ thrust_sp *= k;
+ saturation_xy = true;
+ saturation_z = true;
+ }
+
+ thrust_abs = _params.thr_max;
+ }
+
+ /* update integrals */
+ math::Vector<3> m;
+ m(0) = (_control_mode.flag_control_velocity_enabled && !saturation_xy) ? 1.0f : 0.0f;
+ m(1) = m(0);
+ m(2) = (_control_mode.flag_control_climb_rate_enabled && !saturation_z) ? 1.0f : 0.0f;
+
+ thrust_int += vel_err.emult(_params.vel_i) * dt;
+
+ /* protection against flipping on ground when landing */
+ if (thrust_int(2) > 0.0f)
+ thrust_int(2) = 0.0f;
+
+ /* calculate attitude and thrust from thrust vector */
+ if (_control_mode.flag_control_velocity_enabled) {
+ /* desired body_z axis = -normalize(thrust_vector) */
+ math::Vector<3> body_x;
+ math::Vector<3> body_y;
+ math::Vector<3> body_z;
+
+ if (thrust_abs > SIGMA) {
+ body_z = -thrust_sp / thrust_abs;
+
+ } else {
+ /* no thrust, set Z axis to safe value */
+ body_z.zero();
+ body_z(2) = 1.0f;
+ }
+
+ /* vector of desired yaw direction in XY plane, rotated by PI/2 */
+ math::Vector<3> y_C(-sinf(_att_sp.yaw_body), cosf(_att_sp.yaw_body), 0.0f);
+
+ if (fabsf(body_z(2)) > SIGMA) {
+ /* desired body_x axis, orthogonal to body_z */
+ body_x = y_C % body_z;
+
+ /* keep nose to front while inverted upside down */
+ if (body_z(2) < 0.0f) {
+ body_x = -body_x;
+ }
+ body_x.normalize();
+ } else {
+ /* desired thrust is in XY plane, set X downside to construct correct matrix,
+ * but yaw component will not be used actually */
+ body_x.zero();
+ body_x(2) = 1.0f;
+ }
+
+ /* desired body_y axis */
+ body_y = body_z % body_x;
+
+ /* fill rotation matrix */
+ for (int i = 0; i < 3; i++) {
+ R(i, 0) = body_x(i);
+ R(i, 1) = body_y(i);
+ R(i, 2) = body_z(i);
+ }
+
+ /* copy rotation matrix to attitude setpoint topic */
+ memcpy(&_att_sp.R_body[0][0], R.data, sizeof(_att_sp.R_body));
+ _att_sp.R_valid = true;
+
+ /* calculate euler angles, for logging only, must not be used for control */
+ math::Vector<3> euler = R.to_euler();
+ _att_sp.roll_body = euler(0);
+ _att_sp.pitch_body = euler(1);
+ /* yaw already used to construct rot matrix, but actual rotation matrix can have different yaw near singularity */
+
+ } else {
+ /* thrust compensation for altitude only control mode */
+ float att_comp;
+
+ if (_att.R[2][2] > TILT_COS_MAX)
+ att_comp = 1.0f / _att.R[2][2];
+ else if (_att.R[2][2] > 0.0f)
+ att_comp = ((1.0f / TILT_COS_MAX - 1.0f) / TILT_COS_MAX) * _att.R[2][2] + 1.0f;
+ else
+ att_comp = 1.0f;
+
+ thrust_abs *= att_comp;
+ }
+
+ _att_sp.thrust = thrust_abs;
+
+ _att_sp.timestamp = hrt_absolute_time();
+
+ /* publish attitude setpoint */
+ if (_att_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp);
+
+ } else {
+ _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
+ }
+
+ } else {
+ reset_int_z = true;
+ }
+ } 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;
+ }
+
+ warnx("stopped");
+ mavlink_log_info(mavlink_fd, "[mpc] stopped");
+
+ _control_task = -1;
+ _exit(0);
+}
+
+int
+MulticopterPositionControl::start()
+{
+ ASSERT(_control_task == -1);
+
+ /* start the task */
+ _control_task = task_spawn_cmd("mc_pos_control",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&MulticopterPositionControl::task_main_trampoline,
+ nullptr);
+
+ if (_control_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int mc_pos_control_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: mc_pos_control {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (pos_control::g_control != nullptr)
+ errx(1, "already running");
+
+ pos_control::g_control = new MulticopterPositionControl;
+
+ if (pos_control::g_control == nullptr)
+ errx(1, "alloc failed");
+
+ if (OK != pos_control::g_control->start()) {
+ delete pos_control::g_control;
+ pos_control::g_control = nullptr;
+ err(1, "start failed");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (pos_control::g_control == nullptr)
+ errx(1, "not running");
+
+ delete pos_control::g_control;
+ pos_control::g_control = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (pos_control::g_control) {
+ errx(0, "running");
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c
new file mode 100644
index 000000000..92fa94dcd
--- /dev/null
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -0,0 +1,25 @@
+/*
+ * mc_pos_control_params.c
+ *
+ * Created on: 26.12.2013
+ * Author: ton
+ */
+
+#include <systemlib/param/param.h>
+
+/* multicopter position controller parameters */
+PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_P, 0.1f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_I, 0.02f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f);
+PARAM_DEFINE_FLOAT(MPC_Z_FF, 0.5f);
+PARAM_DEFINE_FLOAT(MPC_XY_P, 1.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_P, 0.1f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_I, 0.02f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
+PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 1.0f);
diff --git a/src/modules/multirotor_pos_control/module.mk b/src/modules/mc_pos_control/module.mk
index bc4b48fb4..1d98173fa 100644
--- a/src/modules/multirotor_pos_control/module.mk
+++ b/src/modules/mc_pos_control/module.mk
@@ -32,11 +32,10 @@
############################################################################
#
-# Build multirotor position control
+# Build multicopter position controller
#
-MODULE_COMMAND = multirotor_pos_control
+MODULE_COMMAND = mc_pos_control
-SRCS = multirotor_pos_control.c \
- multirotor_pos_control_params.c \
- thrust_pid.c
+SRCS = mc_pos_control_main.cpp \
+ mc_pos_control_params.c
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index 8245aa560..b7df0433a 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
@@ -194,8 +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, 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);
+ pid_init(&pitch_controller, PID_MODE_DERIVATIV_SET, 0.0f);
+ pid_init(&roll_controller, PID_MODE_DERIVATIV_SET, 0.0f);
initialized = true;
}
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.c b/src/modules/multirotor_att_control/multirotor_rate_control.c
index 86ac0e4ff..eb41bf93e 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.c
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.c
@@ -161,9 +161,9 @@ void multirotor_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
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);
+ pid_init(&pitch_rate_controller, PID_MODE_DERIVATIV_CALC_NO_SP, 0.003f);
+ pid_init(&roll_rate_controller, PID_MODE_DERIVATIV_CALC_NO_SP, 0.003f);
+ pid_init(&yaw_rate_controller, PID_MODE_DERIVATIV_CALC_NO_SP, 0.003f);
}
/* load new parameters with lower rate */
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
deleted file mode 100644
index b7041e4d5..000000000
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
+++ /dev/null
@@ -1,112 +0,0 @@
-/****************************************************************************
- *
- * 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 multirotor_pos_control_params.c
- *
- * Parameters for multirotor_pos_control
- */
-
-#include "multirotor_pos_control_params.h"
-
-/* controller parameters */
-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)
-{
- 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->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
deleted file mode 100644
index fc658dadb..000000000
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
+++ /dev/null
@@ -1,101 +0,0 @@
-/****************************************************************************
- *
- * 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 multirotor_pos_control_params.h
- *
- * Parameters for multirotor_pos_control
- */
-
-#include <systemlib/param/param.h>
-
-struct multirotor_position_control_params {
- 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 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;
-};
-
-/**
- * Initialize all parameter handles and values
- *
- */
-int parameters_init(struct multirotor_position_control_param_handles *h);
-
-/**
- * Update all parameters
- *
- */
-int parameters_update(const struct multirotor_position_control_param_handles *h, struct multirotor_position_control_params *p);
diff --git a/src/modules/multirotor_pos_control/thrust_pid.c b/src/modules/multirotor_pos_control/thrust_pid.c
deleted file mode 100644
index b985630ae..000000000
--- a/src/modules/multirotor_pos_control/thrust_pid.c
+++ /dev/null
@@ -1,189 +0,0 @@
-/****************************************************************************
- *
- * 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/multirotor_pos_control/thrust_pid.h b/src/modules/multirotor_pos_control/thrust_pid.h
deleted file mode 100644
index 5e169c1ba..000000000
--- a/src/modules/multirotor_pos_control/thrust_pid.h
+++ /dev/null
@@ -1,76 +0,0 @@
-/****************************************************************************
- *
- * 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.h
- *
- * Definition of thrust control PID interface.
- *
- * @author Anton Babushkin <anton.babushkin@me.com>
- */
-
-#ifndef THRUST_PID_H_
-#define THRUST_PID_H_
-
-#include <stdint.h>
-
-__BEGIN_DECLS
-
-/* 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
-
-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;
-
-__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);
-
-__END_DECLS
-
-#endif /* THRUST_PID_H_ */
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 5bf0fba30..52d8c9fe3 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -71,15 +71,21 @@
#include "position_estimator_inav_params.h"
#include "inertial_filter.h"
+#define MIN_VALID_W 0.00001f
+
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 hrt_abstime gps_topic_timeout = 1000000; // GPS topic timeout = 1s
+static const hrt_abstime flow_topic_timeout = 1000000; // optical flow topic timeout = 1s
+static const hrt_abstime sonar_timeout = 150000; // sonar timeout = 150ms
+static const hrt_abstime sonar_valid_timeout = 1000000; // estimate sonar distance during this time after sonar loss
+static const hrt_abstime xy_src_timeout = 2000000; // estimate position during this time after position sources loss
static const uint32_t updates_counter_len = 1000000;
-static const uint32_t pub_interval = 4000; // limit publish rate to 250 Hz
+static const uint32_t pub_interval = 10000; // limit publish rate to 100 Hz
+static const float max_flow = 1.0f; // max flow value that can be used, rad/s
__EXPORT int position_estimator_inav_main(int argc, char *argv[]);
@@ -95,8 +101,7 @@ 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");
+ fprintf(stderr, "usage: position_estimator_inav {start|stop|status} [-v]\n\n");
exit(1);
}
@@ -115,7 +120,7 @@ int position_estimator_inav_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("position_estimator_inav already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
@@ -135,16 +140,23 @@ int position_estimator_inav_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
+ if (thread_running) {
+ warnx("stop");
+ thread_should_exit = true;
+
+ } else {
+ warnx("app not started");
+ }
+
exit(0);
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tposition_estimator_inav is running\n");
+ warnx("app is running");
} else {
- printf("\tposition_estimator_inav not started\n");
+ warnx("app not started");
}
exit(0);
@@ -159,27 +171,74 @@ int position_estimator_inav_main(int argc, char *argv[])
****************************************************************************/
int position_estimator_inav_thread_main(int argc, char *argv[])
{
- warnx("started.");
+ 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 baro_offset = 0.0f; // baro offset for reference altitude, initialized on start, then adjusted
+ float surface_offset = 0.0f; // ground level offset from reference altitude
+ float surface_offset_rate = 0.0f; // surface offset change rate
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;
+ bool ref_inited = false;
+ hrt_abstime ref_init_start = 0;
+ const hrt_abstime ref_init_delay = 1000000; // wait for 1s after 3D fix
+
+ 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();
+
+ hrt_abstime t_prev = 0;
+
+ /* 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 corr_acc[] = { 0.0f, 0.0f, 0.0f }; // N E D
+ float acc_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
+ float corr_baro = 0.0f; // D
+ float corr_gps[3][2] = {
+ { 0.0f, 0.0f }, // N (pos, vel)
+ { 0.0f, 0.0f }, // E (pos, vel)
+ { 0.0f, 0.0f }, // D (pos, vel)
+ };
+ float w_gps_xy = 1.0f;
+ float w_gps_z = 1.0f;
+ float corr_sonar = 0.0f;
+ float corr_sonar_filtered = 0.0f;
+
+ float corr_flow[] = { 0.0f, 0.0f }; // N E
+ float w_flow = 0.0f;
+
+ float sonar_prev = 0.0f;
+ hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
+ hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered)
+ hrt_abstime xy_src_time = 0; // time of last available position data
+
+ bool gps_valid = false; // GPS is valid
+ bool sonar_valid = false; // sonar is valid
+ bool flow_valid = false; // flow is valid
+ bool flow_accurate = false; // flow should be accurate (this flag not updated if flow_valid == false)
+
/* declare and safely initialize all structs */
struct actuator_controls_s actuator;
memset(&actuator, 0, sizeof(actuator));
@@ -247,75 +306,29 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* mean calculation over several measurements */
if (baro_init_cnt < baro_init_num) {
- baro_alt0 += sensor.baro_alt_meter;
+ baro_offset += 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();
+ baro_offset /= (float) baro_init_cnt;
+ warnx("baro offs: %.2f", baro_offset);
+ mavlink_log_info(mavlink_fd, "[inav] baro offs: %.2f", baro_offset);
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 },
+ struct pollfd fds[1] = {
{ .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
+ int ret = poll(fds, 1, 20); // wait maximal 20 ms = 50 Hz minimum rate
hrt_abstime t = hrt_absolute_time();
if (ret < 0) {
@@ -324,40 +337,60 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
continue;
} else if (ret > 0) {
+ /* act on attitude updates */
+
+ /* vehicle attitude */
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+ attitude_updates++;
+
+ bool updated;
+
/* parameter update */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
+ 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 */
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
parameters_update(&pos_inav_param_handles, &params);
}
/* actuator */
- if (fds[1].revents & POLLIN) {
+ orb_check(actuator_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_sub, &actuator);
}
/* armed */
- if (fds[2].revents & POLLIN) {
+ orb_check(armed_sub, &updated);
+
+ if (updated) {
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++;
+ /* reset ground level on arm */
+ if (armed.armed && !flag_armed) {
+ flag_armed = armed.armed;
+ baro_offset -= z_est[0];
+ corr_baro = 0.0f;
+ local_pos.ref_alt -= z_est[0];
+ local_pos.ref_timestamp = t;
+ z_est[0] = 0.0f;
+ alt_avg = 0.0f;
+ }
}
/* sensor combined */
- if (fds[4].revents & POLLIN) {
+ orb_check(sensor_combined_sub, &updated);
+
+ if (updated) {
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];
+ /* correct accel bias */
+ sensor.accelerometer_m_s2[0] -= acc_bias[0];
+ sensor.accelerometer_m_s2[1] -= acc_bias[1];
+ sensor.accelerometer_m_s2[2] -= acc_bias[2];
/* transform acceleration vector from body frame to NED frame */
for (int i = 0; i < 3; i++) {
@@ -368,12 +401,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
- 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];
+ corr_acc[0] = accel_NED[0] - x_est[2];
+ corr_acc[1] = accel_NED[1] - y_est[2];
+ corr_acc[2] = accel_NED[2] + CONSTANTS_ONE_G - z_est[2];
} else {
- memset(accel_corr, 0, sizeof(accel_corr));
+ memset(corr_acc, 0, sizeof(corr_acc));
}
accel_counter = sensor.accelerometer_counter;
@@ -381,180 +414,353 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
if (sensor.baro_counter != baro_counter) {
- baro_corr = - sensor.baro_alt_meter - z_est[0];
+ corr_baro = baro_offset - sensor.baro_alt_meter - z_est[0];
baro_counter = sensor.baro_counter;
baro_updates++;
}
}
/* optical flow */
- if (fds[5].revents & POLLIN) {
+ orb_check(optical_flow_sub, &updated);
+
+ if (updated) {
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;
- }
+ if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && att.R[2][2] > 0.7 && flow.ground_distance_m != sonar_prev) {
+ sonar_time = t;
+ sonar_prev = flow.ground_distance_m;
+ corr_sonar = flow.ground_distance_m + surface_offset + z_est[0];
+ corr_sonar_filtered += (corr_sonar - corr_sonar_filtered) * params.sonar_filt;
+
+ if (fabsf(corr_sonar) > params.sonar_err) {
+ /* correction is too large: spike or new ground level? */
+ if (fabsf(corr_sonar - corr_sonar_filtered) > params.sonar_err) {
+ /* spike detected, ignore */
+ corr_sonar = 0.0f;
+ sonar_valid = false;
+
+ } else {
+ /* new ground level */
+ surface_offset -= corr_sonar;
+ surface_offset_rate = 0.0f;
+ corr_sonar = 0.0f;
+ corr_sonar_filtered = 0.0f;
+ sonar_valid_time = t;
+ sonar_valid = true;
+ local_pos.surface_bottom_timestamp = t;
+ mavlink_log_info(mavlink_fd, "[inav] new surface level: %.2f", surface_offset);
+ }
+
+ } else {
+ /* correction is ok, use it */
+ sonar_valid_time = t;
+ sonar_valid = true;
+ }
+ }
+
+ float flow_q = flow.quality / 255.0f;
+ float dist_bottom = - z_est[0] - surface_offset;
+
+ if (dist_bottom > 0.3f && flow_q > params.flow_q_min && (t < sonar_valid_time + sonar_valid_timeout) && att.R[2][2] > 0.7) {
+ /* distance to surface */
+ float flow_dist = dist_bottom / att.R[2][2];
+ /* check if flow if too large for accurate measurements */
+ /* calculate estimated velocity in body frame */
+ float body_v_est[2] = { 0.0f, 0.0f };
+
+ for (int i = 0; i < 2; i++) {
+ body_v_est[i] = att.R[0][i] * x_est[1] + att.R[1][i] * y_est[1] + att.R[2][i] * z_est[1];
+ }
+
+ /* set this flag if flow should be accurate according to current velocity and attitude rate estimate */
+ flow_accurate = fabsf(body_v_est[1] / flow_dist - att.rollspeed) < max_flow &&
+ fabsf(body_v_est[0] / flow_dist + att.pitchspeed) < max_flow;
+
+ /* convert raw flow to angular flow */
+ float flow_ang[2];
+ flow_ang[0] = flow.flow_raw_x * params.flow_k;
+ flow_ang[1] = flow.flow_raw_y * params.flow_k;
+ /* flow measurements vector */
+ float flow_m[3];
+ flow_m[0] = -flow_ang[0] * flow_dist;
+ flow_m[1] = -flow_ang[1] * flow_dist;
+ flow_m[2] = z_est[1];
+ /* velocity in NED */
+ float flow_v[2] = { 0.0f, 0.0f };
+
+ /* project measurements vector to NED basis, skip Z component */
+ for (int i = 0; i < 2; i++) {
+ for (int j = 0; j < 3; j++) {
+ flow_v[i] += att.R[i][j] * flow_m[j];
}
}
+ /* velocity correction */
+ corr_flow[0] = flow_v[0] - x_est[1];
+ corr_flow[1] = flow_v[1] - y_est[1];
+ /* adjust correction weight */
+ float flow_q_weight = (flow_q - params.flow_q_min) / (1.0f - params.flow_q_min);
+ w_flow = att.R[2][2] * flow_q_weight / fmaxf(1.0f, flow_dist);
+
+ /* if flow is not accurate, reduce weight for it */
+ // TODO make this more fuzzy
+ if (!flow_accurate)
+ w_flow *= 0.05f;
+
+ flow_valid = true;
+
} else {
- sonar_corr = 0.0f;
+ w_flow = 0.0f;
+ flow_valid = false;
}
flow_updates++;
}
/* vehicle GPS position */
- if (fds[6].revents & POLLIN) {
+ orb_check(vehicle_gps_position_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
- if (gps.fix_type >= 3 && t < gps.timestamp_position + gps_timeout) {
+ if (gps.fix_type >= 3) {
+ /* hysteresis for GPS quality */
+ if (gps_valid) {
+ if (gps.eph_m > 10.0f || gps.epv_m > 10.0f) {
+ gps_valid = false;
+ mavlink_log_info(mavlink_fd, "[inav] GPS signal lost");
+ }
+
+ } else {
+ if (gps.eph_m < 5.0f && gps.epv_m < 5.0f) {
+ gps_valid = true;
+ mavlink_log_info(mavlink_fd, "[inav] GPS signal found");
+ }
+ }
+
+ } else {
+ gps_valid = false;
+ }
+
+ if (gps_valid) {
/* 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_inited) {
+ if (ref_init_start == 0) {
+ ref_init_start = t;
+
+ } else if (t > ref_init_start + ref_init_delay) {
+ ref_inited = true;
+ /* reference GPS position */
+ double lat = gps.lat * 1e-7;
+ double lon = gps.lon * 1e-7;
+ float alt = gps.alt * 1e-3;
+
+ local_pos.ref_lat = gps.lat;
+ local_pos.ref_lon = gps.lon;
+ local_pos.ref_alt = alt + z_est[0];
+ local_pos.ref_timestamp = t;
+
+ /* initialize projection */
+ map_projection_init(lat, lon);
+ warnx("init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
+ mavlink_log_info(mavlink_fd, "[inav] init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
}
}
- if (ref_xy_inited) {
+ if (ref_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];
+ corr_gps[0][0] = gps_proj[0] - x_est[0];
+ corr_gps[1][0] = gps_proj[1] - y_est[0];
+ corr_gps[2][0] = local_pos.ref_alt - gps.alt * 1e-3 - z_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];
+ corr_gps[0][1] = gps.vel_n_m_s - x_est[1];
+ corr_gps[1][1] = gps.vel_e_m_s - y_est[1];
+ corr_gps[2][1] = gps.vel_d_m_s - z_est[1];
} else {
- gps_corr[0][1] = 0.0f;
- gps_corr[1][1] = 0.0f;
+ corr_gps[0][1] = 0.0f;
+ corr_gps[1][1] = 0.0f;
+ corr_gps[2][1] = 0.0f;
}
+
+ w_gps_xy = 1.0f / fmaxf(1.0f, gps.eph_m);
+ w_gps_z = 1.0f / fmaxf(1.0f, gps.epv_m);
}
} else {
/* no GPS lock */
- memset(gps_corr, 0, sizeof(gps_corr));
- ref_xy_init_start = 0;
+ memset(corr_gps, 0, sizeof(corr_gps));
+ ref_init_start = 0;
}
gps_updates++;
}
}
- /* end of poll return value check */
+ /* check for timeout on FLOW topic */
+ if ((flow_valid || sonar_valid) && t > flow.timestamp + flow_topic_timeout) {
+ flow_valid = false;
+ sonar_valid = false;
+ warnx("FLOW timeout");
+ mavlink_log_info(mavlink_fd, "[inav] FLOW timeout");
+ }
+
+ /* check for timeout on GPS topic */
+ if (gps_valid && t > gps.timestamp_position + gps_topic_timeout) {
+ gps_valid = false;
+ warnx("GPS timeout");
+ mavlink_log_info(mavlink_fd, "[inav] GPS timeout");
+ }
+
+ /* check for sonar measurement timeout */
+ if (sonar_valid && t > sonar_time + sonar_timeout) {
+ corr_sonar = 0.0f;
+ sonar_valid = false;
+ }
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);
+ /* use GPS if it's valid and reference position initialized */
+ bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
+ bool use_gps_z = ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W;
+ /* use flow if it's valid and (accurate or no GPS available) */
+ bool use_flow = flow_valid && (flow_accurate || !use_gps_xy);
+
+ /* try to estimate position during some time after position sources lost */
+ if (use_gps_xy || use_flow) {
+ xy_src_time = t;
+ }
+
+ bool can_estimate_xy = (t < xy_src_time + xy_src_timeout);
+
+ bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
+
+ if (dist_bottom_valid) {
+ /* surface distance prediction */
+ surface_offset += surface_offset_rate * dt;
+
+ /* surface distance correction */
+ if (sonar_valid) {
+ surface_offset_rate -= corr_sonar * 0.5f * params.w_z_sonar * params.w_z_sonar * dt;
+ surface_offset -= corr_sonar * params.w_z_sonar * dt;
+ }
+ }
+
+ float w_xy_gps_p = params.w_xy_gps_p * w_gps_xy;
+ float w_xy_gps_v = params.w_xy_gps_v * w_gps_xy;
+ float w_z_gps_p = params.w_z_gps_p * w_gps_z;
+
+ /* reduce GPS weight if optical flow is good */
+ if (use_flow && flow_accurate) {
+ w_xy_gps_p *= params.w_gps_flow;
+ w_xy_gps_v *= params.w_gps_flow;
+ }
+
+ /* baro offset correction */
+ if (use_gps_z) {
+ float offs_corr = corr_gps[2][0] * w_z_gps_p * dt;
+ baro_offset += offs_corr;
+ baro_counter += offs_corr;
}
- /* 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;
+ /* accelerometer bias correction */
+ float accel_bias_corr[3] = { 0.0f, 0.0f, 0.0f };
+
+ if (use_gps_xy) {
+ accel_bias_corr[0] -= corr_gps[0][0] * w_xy_gps_p * w_xy_gps_p;
+ accel_bias_corr[0] -= corr_gps[0][1] * w_xy_gps_v;
+ accel_bias_corr[1] -= corr_gps[1][0] * w_xy_gps_p * w_xy_gps_p;
+ accel_bias_corr[1] -= corr_gps[1][1] * w_xy_gps_v;
+ }
+
+ if (use_gps_z) {
+ accel_bias_corr[2] -= corr_gps[2][0] * w_z_gps_p * w_z_gps_p;
+ }
+
+ if (use_flow) {
+ accel_bias_corr[0] -= corr_flow[0] * params.w_xy_flow;
+ accel_bias_corr[1] -= corr_flow[1] * params.w_xy_flow;
+ }
+
+ accel_bias_corr[2] -= corr_baro * params.w_z_baro * params.w_z_baro;
+
+ /* transform error vector from NED frame to body frame */
+ for (int i = 0; i < 3; i++) {
+ float c = 0.0f;
+
+ for (int j = 0; j < 3; j++) {
+ c += att.R[j][i] * accel_bias_corr[j];
+ }
+
+ acc_bias[i] += c * 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;
+ inertial_filter_correct(corr_baro, dt, z_est, 0, params.w_z_baro);
+ inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
+ inertial_filter_correct(corr_acc[2], dt, z_est, 2, params.w_z_acc);
if (can_estimate_xy) {
/* inertial filter prediction for position */
inertial_filter_predict(dt, x_est);
inertial_filter_predict(dt, y_est);
+ if (!isfinite(x_est[0]) || !isfinite(y_est[0])) {
+ warnx("BAD ESTIMATE AFTER PREDICTION %.6f x: %.3f %.3f %.3f y: %.3f %.3f %.3f", dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2]);
+ thread_should_exit = true;
+ }
+
/* 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);
+ inertial_filter_correct(corr_acc[0], dt, x_est, 2, params.w_xy_acc);
+ inertial_filter_correct(corr_acc[1], dt, y_est, 2, params.w_xy_acc);
+
+ if (use_flow) {
+ inertial_filter_correct(corr_flow[0], dt, x_est, 1, params.w_xy_flow * w_flow);
+ inertial_filter_correct(corr_flow[1], dt, y_est, 1, params.w_xy_flow * w_flow);
+ }
- 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 (use_gps_xy) {
+ inertial_filter_correct(corr_gps[0][0], dt, x_est, 0, w_xy_gps_p);
+ inertial_filter_correct(corr_gps[1][0], dt, y_est, 0, w_xy_gps_v);
- 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);
+ if (gps.vel_ned_valid && t < gps.timestamp_velocity + gps_topic_timeout) {
+ inertial_filter_correct(corr_gps[0][1], dt, x_est, 1, w_xy_gps_v);
+ inertial_filter_correct(corr_gps[1][1], dt, y_est, 1, w_xy_gps_v);
}
}
+
+ if (!isfinite(x_est[0]) || !isfinite(y_est[0])) {
+ warnx("BAD ESTIMATE AFTER CORRECTION dt: %.6f x: %.3f %.3f %.3f y: %.3f %.3f %.3f", dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2]);
+ warnx("BAD ESTIMATE AFTER CORRECTION acc: %.3f %.3f gps x: %.3f %.3f gps y: %.3f %.3f", corr_acc[0], corr_acc[1], corr_gps[0][0], corr_gps[0][1], corr_gps[1][0], corr_gps[1][1]);
+ thread_should_exit = true;
+ }
}
/* 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;
+ alt_avg += (- z_est[0] - alt_avg) * dt / params.land_t;
+ float alt_disp2 = - z_est[0] - alt_avg;
+ alt_disp2 = alt_disp2 * alt_disp2;
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) {
+ if (alt_disp2 > land_disp2 && thrust > params.land_thr) {
landed = false;
landed_time = 0;
}
} else {
- if (alt_disp < land_disp2 && thrust < params.land_thr) {
+ if (alt_disp2 < land_disp2 && thrust < params.land_thr) {
if (landed_time == 0) {
landed_time = t; // land detected first time
@@ -593,10 +799,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
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.xy_valid = can_estimate_xy && use_gps_xy;
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.xy_global = local_pos.xy_valid && use_gps_xy;
+ local_pos.z_global = local_pos.z_valid && use_gps_z;
local_pos.x = x_est[0];
local_pos.vx = x_est[1];
local_pos.y = y_est[0];
@@ -605,6 +811,14 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.vz = z_est[1];
local_pos.landed = landed;
local_pos.yaw = att.yaw;
+ local_pos.dist_bottom_valid = dist_bottom_valid;
+
+ if (local_pos.dist_bottom_valid) {
+ local_pos.dist_bottom = -z_est[0] - surface_offset;
+ local_pos.dist_bottom_rate = -z_est[1] - surface_offset_rate;
+ }
+
+ local_pos.timestamp = t;
orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos);
@@ -636,17 +850,17 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
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");
+ warnx("stopped");
+ mavlink_log_info(mavlink_fd, "[inav] stopped");
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
index 4f9ddd009..da4c9482c 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -40,16 +40,19 @@
#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_Z_BARO, 1.0f);
+PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.5f);
+PARAM_DEFINE_FLOAT(INAV_W_Z_ACC, 20.0f);
+PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f);
+PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
+PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
+PARAM_DEFINE_FLOAT(INAV_W_XY_ACC, 10.0f);
+PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f);
+PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
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_FLOW_K, 0.0165f);
+PARAM_DEFINE_FLOAT(INAV_FLOW_Q_MIN, 0.5f);
+PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.05f);
PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
@@ -57,15 +60,18 @@ 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_z_baro = param_find("INAV_W_Z_BARO");
+ h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
+ h->w_z_acc = param_find("INAV_W_Z_ACC");
+ h->w_z_sonar = param_find("INAV_W_Z_SONAR");
+ h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
+ h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
+ h->w_xy_acc = param_find("INAV_W_XY_ACC");
+ h->w_xy_flow = param_find("INAV_W_XY_FLOW");
+ h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
h->flow_k = param_find("INAV_FLOW_K");
+ h->flow_q_min = param_find("INAV_FLOW_Q_MIN");
h->sonar_filt = param_find("INAV_SONAR_FILT");
h->sonar_err = param_find("INAV_SONAR_ERR");
h->land_t = param_find("INAV_LAND_T");
@@ -77,15 +83,18 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
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_z_baro, &(p->w_z_baro));
+ param_get(h->w_z_gps_p, &(p->w_z_gps_p));
+ param_get(h->w_z_acc, &(p->w_z_acc));
+ param_get(h->w_z_sonar, &(p->w_z_sonar));
+ param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
+ param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
+ param_get(h->w_xy_acc, &(p->w_xy_acc));
+ param_get(h->w_xy_flow, &(p->w_xy_flow));
+ param_get(h->w_gps_flow, &(p->w_gps_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
param_get(h->flow_k, &(p->flow_k));
+ param_get(h->flow_q_min, &(p->flow_q_min));
param_get(h->sonar_filt, &(p->sonar_filt));
param_get(h->sonar_err, &(p->sonar_err));
param_get(h->land_t, &(p->land_t));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index 61570aea7..e2be079d3 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -41,15 +41,18 @@
#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_z_baro;
+ float w_z_gps_p;
+ float w_z_acc;
+ float w_z_sonar;
+ float w_xy_gps_p;
+ float w_xy_gps_v;
+ float w_xy_acc;
+ float w_xy_flow;
+ float w_gps_flow;
float w_acc_bias;
float flow_k;
+ float flow_q_min;
float sonar_filt;
float sonar_err;
float land_t;
@@ -58,15 +61,18 @@ struct position_estimator_inav_params {
};
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_z_baro;
+ param_t w_z_gps_p;
+ param_t w_z_acc;
+ param_t w_z_sonar;
+ param_t w_xy_gps_p;
+ param_t w_xy_gps_v;
+ param_t w_xy_acc;
+ param_t w_xy_flow;
+ param_t w_gps_flow;
param_t w_acc_bias;
param_t flow_k;
+ param_t flow_q_min;
param_t sonar_filt;
param_t sonar_err;
param_t land_t;
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index f630b6f2a..541eed0e1 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -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;
@@ -94,7 +94,7 @@ controls_tick() {
* other. Don't do that.
*/
- /* receive signal strenght indicator (RSSI). 0 = no connection, 1000: perfect connection */
+ /* receive signal strenght indicator (RSSI). 0 = no connection, 255: perfect connection */
uint16_t rssi = 0;
perf_begin(c_gather_dsm);
@@ -108,7 +108,7 @@ controls_tick() {
else
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11;
- rssi = 1000;
+ rssi = 255;
}
perf_end(c_gather_dsm);
@@ -125,11 +125,11 @@ 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);
+ bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_status[PX4IO_P_STATUS_RC_DATA]);
if (ppm_updated) {
/* XXX sample RSSI properly here */
- rssi = 1000;
+ rssi = 255;
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
}
@@ -321,7 +321,7 @@ controls_tick() {
}
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;
@@ -345,6 +345,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/protocol.h b/src/modules/px4iofirmware/protocol.h
index c10f0167c..e5bef6eb3 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -128,7 +128,8 @@
#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 */
-#define PX4IO_P_STATUS_NRSSI 9 /* [2] Normalized RSSI value, 0: no reception, 1000: perfect reception */
+#define PX4IO_P_STATUS_NRSSI 9 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
+#define PX4IO_P_STATUS_RC_DATA 10 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
/* array of post-mix actuator outputs, -10000..10000 */
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index 6aca2bd11..11ccd7356 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -280,7 +280,7 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint
*rssi = 100; // XXX magic number indicating bad signal, but not a signal loss (yet)
}
- *rssi = 1000;
+ *rssi = 255;
return true;
}
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 9f634d9e4..c6648de05 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -752,6 +752,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_GPSP_s log_GPSP;
struct log_ESC_s log_ESC;
struct log_GVSP_s log_GVSP;
+ struct log_DIST_s log_DIST;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -909,6 +910,9 @@ int sdlog2_thread_main(int argc, char *argv[])
uint16_t baro_counter = 0;
uint16_t differential_pressure_counter = 0;
+ /* track changes in distance status */
+ bool dist_bottom_present = false;
+
/* enable logging on start if needed */
if (log_on_start)
sdlog2_start_log();
@@ -1122,6 +1126,17 @@ int sdlog2_thread_main(int argc, char *argv[])
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);
+
+ if (buf.local_pos.dist_bottom_valid) {
+ dist_bottom_present = true;
+ }
+ if (dist_bottom_present) {
+ log_msg.msg_type = LOG_DIST_MSG;
+ log_msg.body.log_DIST.bottom = buf.local_pos.dist_bottom;
+ log_msg.body.log_DIST.bottom_rate = buf.local_pos.dist_bottom_rate;
+ log_msg.body.log_DIST.flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
+ LOGBUFFER_WRITE_AND_COUNT(DIST);
+ }
}
/* --- LOCAL POSITION SETPOINT --- */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index cb1393f1f..ff58d23f6 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -247,6 +247,16 @@ struct log_GVSP_s {
float vz;
};
+/* --- DIST - DISTANCE TO SURFACE --- */
+#define LOG_DIST_MSG 20
+struct log_DIST_s {
+ float bottom;
+ float bottom_rate;
+ uint8_t flags;
+};
+
+/********** SYSTEM MESSAGES, ID > 0x80 **********/
+
/* --- TIME - TIME STAMP --- */
#define LOG_TIME_MSG 129
struct log_TIME_s {
@@ -290,6 +300,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(GPSP, "BLLffBfbfff", "AltRel,Lat,Lon,Alt,Yaw,NavCmd,LoitRad,LoitDir,Rad,TimeIn,pitMin"),
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(DIST, "ffB", "Bottom,BottomRate,Flags"),
/* system-level messages, ID >= 0x80 */
// FMT: don't write format of format message, it's useless
LOG_FORMAT(TIME, "Q", "StartTime"),
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index d9f037c27..66491500e 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -211,8 +211,8 @@ 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 */
+ math::Matrix<3,3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
+ math::Matrix<3,3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
bool _mag_is_external; /**< true if the active mag is on an external board */
struct {
@@ -465,8 +465,6 @@ Sensors::Sensors() :
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "sensor task update")),
- _board_rotation(3, 3),
- _external_mag_rotation(3, 3),
_mag_is_external(false)
{
@@ -920,7 +918,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
- math::Vector3 vect = {accel_report.x, accel_report.y, accel_report.z};
+ math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z);
vect = _board_rotation * vect;
raw.accelerometer_m_s2[0] = vect(0);
@@ -946,7 +944,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);
- math::Vector3 vect = {gyro_report.x, gyro_report.y, gyro_report.z};
+ math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z);
vect = _board_rotation * vect;
raw.gyro_rad_s[0] = vect(0);
@@ -972,7 +970,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_mag), _mag_sub, &mag_report);
- math::Vector3 vect = {mag_report.x, mag_report.y, mag_report.z};
+ math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z);
if (_mag_is_external)
vect = _external_mag_rotation * vect;
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 77c952f52..6a4e9392a 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -39,7 +39,7 @@
/**
* @file pid.c
*
- * Implementation of generic PID control interface.
+ * Implementation of generic PID controller.
*
* @author Laurens Mackay <mackayl@student.ethz.ch>
* @author Tobias Naegeli <naegelit@student.ethz.ch>
@@ -53,24 +53,21 @@
#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 dt_min)
+__EXPORT void pid_init(PID_t *pid, uint8_t mode, float dt_min)
{
- pid->kp = kp;
- pid->ki = ki;
- pid->kd = kd;
- pid->intmax = intmax;
- pid->limit = limit;
pid->mode = mode;
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->kp = 0.0f;
+ pid->ki = 0.0f;
+ pid->kd = 0.0f;
pid->integral = 0.0f;
+ pid->integral_limit = 0.0f;
+ pid->output_limit = 0.0f;
+ pid->error_previous = 0.0f;
+ pid->last_output = 0.0f;
}
-__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax, float limit)
+
+__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float integral_limit, float output_limit)
{
int ret = 0;
@@ -95,15 +92,15 @@ __EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float
ret = 1;
}
- if (isfinite(intmax)) {
- pid->intmax = intmax;
+ if (isfinite(integral_limit)) {
+ pid->integral_limit = integral_limit;
} else {
ret = 1;
}
- if (isfinite(limit)) {
- pid->limit = limit;
+ if (isfinite(output_limit)) {
+ pid->output_limit = output_limit;
} else {
ret = 1;
@@ -112,42 +109,18 @@ __EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float
return ret;
}
-//void pid_set(PID_t *pid, float sp)
-//{
-// pid->sp = sp;
-// pid->error_previous = 0;
-// pid->integral = 0;
-//}
-
-/**
- *
- * @param pid
- * @param val
- * @param dt
- * @return
- */
__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt)
{
- /* error = setpoint - actual_position
- integral = integral + (error*dt)
- derivative = (error - previous_error)/dt
- output = (Kp*error) + (Ki*integral) + (Kd*derivative)
- previous_error = error
- wait(dt)
- goto start
- */
-
if (!isfinite(sp) || !isfinite(val) || !isfinite(val_dot) || !isfinite(dt)) {
return pid->last_output;
}
float i, d;
- pid->sp = sp;
- // Calculated current error value
- float error = pid->sp - val;
+ /* current error value */
+ float error = sp - val;
- // Calculate or measured current error derivative
+ /* current error derivative */
if (pid->mode == PID_MODE_DERIVATIV_CALC) {
d = (error - pid->error_previous) / fmaxf(dt, pid->dt_min);
pid->error_previous = error;
@@ -167,39 +140,34 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
d = 0.0f;
}
- if (pid->ki > 0.0f) {
+ /* calculate PD output */
+ float output = (error * pid->kp) + (d * pid->kd);
+
+ if (pid->ki > SIGMA) {
// Calculate the error integral and check for saturation
i = pid->integral + (error * dt);
- 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;
+ /* check for saturation */
+ if (isfinite(i)) {
+ if ((pid->output_limit < SIGMA || (fabsf(output + (i * pid->ki)) <= pid->output_limit)) &&
+ fabsf(i) <= pid->integral_limit) {
+ /* not saturated, use new integral value */
+ pid->integral = i;
}
-
- pid->integral = i;
- pid->saturated = 0;
}
- } else {
- i = 0.0f;
- pid->saturated = 0;
+ /* add I component to output */
+ output += pid->integral * pid->ki;
}
- // Calculate the output. Limit output magnitude to pid->limit
- float output = (error * pid->kp) + (i * pid->ki) + (d * pid->kd);
-
+ /* limit output */
if (isfinite(output)) {
- if (pid->limit > SIGMA) {
- if (output > pid->limit) {
- output = pid->limit;
+ if (pid->output_limit > SIGMA) {
+ if (output > pid->output_limit) {
+ output = pid->output_limit;
- } else if (output < -pid->limit) {
- output = -pid->limit;
+ } else if (output < -pid->output_limit) {
+ output = -pid->output_limit;
}
}
@@ -212,5 +180,5 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
__EXPORT void pid_reset_integral(PID_t *pid)
{
- pid->integral = 0;
+ pid->integral = 0.0f;
}
diff --git a/src/modules/systemlib/pid/pid.h b/src/modules/systemlib/pid/pid.h
index eca228464..e8b1aac4f 100644
--- a/src/modules/systemlib/pid/pid.h
+++ b/src/modules/systemlib/pid/pid.h
@@ -39,7 +39,7 @@
/**
* @file pid.h
*
- * Definition of generic PID control interface.
+ * Definition of generic PID controller.
*
* @author Laurens Mackay <mackayl@student.ethz.ch>
* @author Tobias Naegeli <naegelit@student.ethz.ch>
@@ -55,38 +55,35 @@
__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 2
-// Use PID_MODE_DERIVATIV_NONE for a PI controller (vs PID)
-#define PID_MODE_DERIVATIV_NONE 9
+typedef enum PID_MODE {
+ /* Use PID_MODE_DERIVATIV_NONE for a PI controller (vs PID) */
+ PID_MODE_DERIVATIV_NONE = 0,
+ /* PID_MODE_DERIVATIV_CALC calculates discrete derivative from previous error,
+ * val_dot in pid_calculate() will be ignored */
+ PID_MODE_DERIVATIV_CALC,
+ /* PID_MODE_DERIVATIV_CALC_NO_SP calculates discrete derivative from previous value,
+ * setpoint derivative will be ignored, val_dot in pid_calculate() will be ignored */
+ PID_MODE_DERIVATIV_CALC_NO_SP,
+ /* Use PID_MODE_DERIVATIV_SET if you have the derivative already (Gyros, Kalman) */
+ PID_MODE_DERIVATIV_SET
+} pid_mode_t;
typedef struct {
+ pid_mode_t mode;
+ float dt_min;
float kp;
float ki;
float kd;
- float intmax;
- float sp;
float integral;
+ float integral_limit;
+ float output_limit;
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, 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 void pid_init(PID_t *pid, pid_mode_t mode, float dt_min);
+__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float integral_limit, float output_limit);
__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
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/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
index 1a245132a..7596f944f 100644
--- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
@@ -61,7 +61,7 @@ struct vehicle_attitude_setpoint_s
float yaw_body; /**< body angle in NED frame */
//float body_valid; /**< Set to true if body angles are valid */
- float R_body[9]; /**< Rotation matrix describing the setpoint as rotation from the current body frame */
+ float R_body[3][3]; /**< 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
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index 427153782..d567f2e02 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -77,6 +77,11 @@ struct vehicle_local_position_s
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 */
+ /* Distance to surface */
+ float dist_bottom; /**< Distance to bottom surface (ground) */
+ float dist_bottom_rate; /**< Distance to bottom surface (ground) change rate */
+ uint64_t surface_bottom_timestamp; /**< Time when new bottom surface found */
+ bool dist_bottom_valid; /**< true if distance to bottom surface is valid */
};
/**
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 68a080c77..4fbd296d2 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -24,6 +24,7 @@ SRCS = test_adc.c \
test_uart_loopback.c \
test_uart_send.c \
test_mixer.cpp \
+ test_mathlib.cpp \
test_file.c \
tests_main.c \
test_param.c \
diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp
new file mode 100644
index 000000000..693a208ba
--- /dev/null
+++ b/src/systemcmds/tests/test_mathlib.cpp
@@ -0,0 +1,159 @@
+/****************************************************************************
+ *
+ * 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 test_mathlib.cpp
+ *
+ * Mathlib test
+ */
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <time.h>
+#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+
+#include "tests.h"
+
+#define TEST_OP(_title, _op) { unsigned int n = 60000; hrt_abstime t0, t1; t0 = hrt_absolute_time(); for (unsigned int j = 0; j < n; j++) { _op; }; t1 = hrt_absolute_time(); warnx(_title ": %.6fus", (double)(t1 - t0) / n); }
+
+using namespace math;
+
+const char* formatResult(bool res) {
+ return res ? "OK" : "ERROR";
+}
+
+int test_mathlib(int argc, char *argv[])
+{
+ warnx("testing mathlib");
+
+ {
+ Vector<2> v;
+ Vector<2> v1(1.0f, 2.0f);
+ Vector<2> v2(1.0f, -1.0f);
+ float data[2] = {1.0f, 2.0f};
+ TEST_OP("Constructor Vector<2>()", Vector<2> v3);
+ TEST_OP("Constructor Vector<2>(Vector<2>)", Vector<2> v3(v1));
+ TEST_OP("Constructor Vector<2>(float[])", Vector<2> v3(data));
+ TEST_OP("Constructor Vector<2>(float, float)", Vector<2> v3(1.0f, 2.0f));
+ TEST_OP("Vector<2> = Vector<2>", v = v1);
+ TEST_OP("Vector<2> + Vector<2>", v + v1);
+ TEST_OP("Vector<2> - Vector<2>", v - v1);
+ TEST_OP("Vector<2> += Vector<2>", v += v1);
+ TEST_OP("Vector<2> -= Vector<2>", v -= v1);
+ TEST_OP("Vector<2> * Vector<2>", v * v1);
+ TEST_OP("Vector<2> %% Vector<2>", v1 % v2);
+ }
+
+ {
+ Vector<3> v;
+ Vector<3> v1(1.0f, 2.0f, 0.0f);
+ Vector<3> v2(1.0f, -1.0f, 2.0f);
+ float data[3] = {1.0f, 2.0f, 3.0f};
+ TEST_OP("Constructor Vector<3>()", Vector<3> v3);
+ TEST_OP("Constructor Vector<3>(Vector<3>)", Vector<3> v3(v1));
+ TEST_OP("Constructor Vector<3>(float[])", Vector<3> v3(data));
+ TEST_OP("Constructor Vector<3>(float, float, float)", Vector<3> v3(1.0f, 2.0f, 3.0f));
+ TEST_OP("Vector<3> = Vector<3>", v = v1);
+ TEST_OP("Vector<3> + Vector<3>", v + v1);
+ TEST_OP("Vector<3> - Vector<3>", v - v1);
+ TEST_OP("Vector<3> += Vector<3>", v += v1);
+ TEST_OP("Vector<3> -= Vector<3>", v -= v1);
+ TEST_OP("Vector<3> * float", v1 * 2.0f);
+ TEST_OP("Vector<3> / float", v1 / 2.0f);
+ TEST_OP("Vector<3> *= float", v1 *= 2.0f);
+ TEST_OP("Vector<3> /= float", v1 /= 2.0f);
+ TEST_OP("Vector<3> * Vector<3>", v * v1);
+ TEST_OP("Vector<3> %% Vector<3>", v1 % v2);
+ TEST_OP("Vector<3> length", v1.length());
+ TEST_OP("Vector<3> length squared", v1.length_squared());
+ TEST_OP("Vector<3> element read", volatile float a = v1(0));
+ TEST_OP("Vector<3> element read direct", volatile float a = v1.data[0]);
+ TEST_OP("Vector<3> element write", v1(0) = 1.0f);
+ TEST_OP("Vector<3> element write direct", v1.data[0] = 1.0f);
+ }
+
+ {
+ Vector<4> v;
+ Vector<4> v1(1.0f, 2.0f, 0.0f, -1.0f);
+ Vector<4> v2(1.0f, -1.0f, 2.0f, 0.0f);
+ float data[4] = {1.0f, 2.0f, 3.0f, 4.0f};
+ TEST_OP("Constructor Vector<4>()", Vector<4> v3);
+ TEST_OP("Constructor Vector<4>(Vector<4>)", Vector<4> v3(v1));
+ TEST_OP("Constructor Vector<4>(float[])", Vector<4> v3(data));
+ TEST_OP("Constructor Vector<4>(float, float, float, float)", Vector<4> v3(1.0f, 2.0f, 3.0f, 4.0f));
+ TEST_OP("Vector<4> = Vector<4>", v = v1);
+ TEST_OP("Vector<4> + Vector<4>", v + v1);
+ TEST_OP("Vector<4> - Vector<4>", v - v1);
+ TEST_OP("Vector<4> += Vector<4>", v += v1);
+ TEST_OP("Vector<4> -= Vector<4>", v -= v1);
+ TEST_OP("Vector<4> * Vector<4>", v * v1);
+ }
+
+ {
+ Vector<10> v1;
+ v1.zero();
+ float data[10];
+ TEST_OP("Constructor Vector<10>()", Vector<10> v3);
+ TEST_OP("Constructor Vector<10>(Vector<10>)", Vector<10> v3(v1));
+ TEST_OP("Constructor Vector<10>(float[])", Vector<10> v3(data));
+ }
+
+ {
+ Matrix<3, 3> m1;
+ m1.identity();
+ Matrix<3, 3> m2;
+ m2.identity();
+ Vector<3> v1(1.0f, 2.0f, 0.0f);
+ TEST_OP("Matrix<3, 3> * Vector<3>", m1 * v1);
+ TEST_OP("Matrix<3, 3> + Matrix<3, 3>", m1 + m2);
+ TEST_OP("Matrix<3, 3> * Matrix<3, 3>", m1 * m2);
+ }
+
+ {
+ Matrix<10, 10> m1;
+ m1.identity();
+ Matrix<10, 10> m2;
+ m2.identity();
+ Vector<10> v1;
+ v1.zero();
+ TEST_OP("Matrix<10, 10> * Vector<10>", m1 * v1);
+ TEST_OP("Matrix<10, 10> + Matrix<10, 10>", m1 + m2);
+ TEST_OP("Matrix<10, 10> * Matrix<10, 10>", m1 * m2);
+ }
+
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index a57d04be3..6420d3798 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -109,6 +109,7 @@ extern int test_bson(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);
extern int test_mixer(int argc, char *argv[]);
extern int test_rc(int argc, char *argv[]);
+extern int test_mathlib(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 1088a4407..5fab8f82e 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -106,6 +106,7 @@ const struct {
{"file", test_file, 0},
{"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
{"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST},
+ {"mathlib", test_mathlib, 0},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};