aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-10-23 14:49:11 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-10-23 14:49:11 +0200
commit3546ded54ef14f7b208572fa86c695c58a18d8fd (patch)
treeb50725423120687f0a01fe2f89fcb434834bf7af
parent114b7b696d54d031c899db4ffb91c125204fbba2 (diff)
parent17ddc7f47198116447612f5bc7707c079956f3e1 (diff)
downloadpx4-firmware-3546ded54ef14f7b208572fa86c695c58a18d8fd.tar.gz
px4-firmware-3546ded54ef14f7b208572fa86c695c58a18d8fd.tar.bz2
px4-firmware-3546ded54ef14f7b208572fa86c695c58a18d8fd.zip
Merge branch 'master' into sdlog2_ver
-rw-r--r--Documentation/l1_control.odgbin0 -> 11753 bytes
-rw-r--r--ROMFS/px4fmu_common/init.d/1000_rc_fw.hil2
-rw-r--r--ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil110
-rw-r--r--ROMFS/px4fmu_common/init.d/100_mpx_easystar5
-rw-r--r--ROMFS/px4fmu_common/init.d/101_hk_bixler5
-rw-r--r--ROMFS/px4fmu_common/init.d/12-13_hex95
-rw-r--r--ROMFS/px4fmu_common/init.d/31_io_phantom2
-rw-r--r--ROMFS/px4fmu_common/init.d/40_io_segway2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_io_esc4
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS62
-rw-r--r--Tools/px4params/README.md9
-rw-r--r--Tools/px4params/dokuwikiout.py27
-rw-r--r--Tools/px4params/output.py5
-rw-r--r--Tools/px4params/parser.py220
-rwxr-xr-xTools/px4params/px_process_params.py61
-rw-r--r--Tools/px4params/scanner.py34
-rw-r--r--Tools/px4params/xmlout.py22
-rw-r--r--Tools/tests-host/.gitignore2
-rw-r--r--Tools/tests-host/Makefile39
-rw-r--r--Tools/tests-host/arch/board/board.h0
-rw-r--r--Tools/tests-host/mixer_test.cpp12
-rw-r--r--Tools/tests-host/nuttx/config.h0
-rw-r--r--makefiles/config_px4fmu-v1_default.mk5
-rw-r--r--makefiles/config_px4fmu-v2_default.mk4
-rw-r--r--mavlink/include/mavlink/v1.0/mavlink_conversions.h12
-rw-r--r--src/drivers/drv_accel.h2
-rw-r--r--src/drivers/rgbled/rgbled.cpp53
-rw-r--r--src/drivers/roboclaw/RoboClaw.cpp328
-rw-r--r--src/drivers/roboclaw/RoboClaw.hpp192
-rw-r--r--src/drivers/roboclaw/module.mk41
-rw-r--r--src/drivers/roboclaw/roboclaw_main.cpp195
-rw-r--r--src/lib/conversion/module.mk38
-rw-r--r--src/lib/conversion/rotation.cpp62
-rw-r--r--src/lib/conversion/rotation.h121
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.cpp33
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp322
-rw-r--r--src/modules/commander/calibration_messages.h57
-rw-r--r--src/modules/commander/commander.cpp58
-rw-r--r--src/modules/commander/gyro_calibration.cpp270
-rw-r--r--src/modules/commander/mag_calibration.cpp276
-rw-r--r--src/modules/commander/module.mk1
-rw-r--r--src/modules/sdlog2/sdlog2.c11
-rw-r--r--src/modules/segway/BlockSegwayController.cpp13
-rw-r--r--src/modules/sensors/sensor_params.c26
-rw-r--r--src/modules/sensors/sensors.cpp93
-rw-r--r--src/modules/systemlib/mixer/mixer.cpp29
-rw-r--r--src/modules/systemlib/mixer/mixer.h25
-rw-r--r--src/modules/systemlib/mixer/mixer_group.cpp15
-rw-r--r--src/modules/systemlib/mixer/mixer_load.c100
-rw-r--r--src/modules/systemlib/mixer/mixer_load.h51
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp14
-rw-r--r--src/modules/systemlib/mixer/mixer_simple.cpp62
-rw-r--r--src/modules/systemlib/mixer/module.mk3
-rw-r--r--src/modules/systemlib/param/param.c85
-rw-r--r--src/modules/systemlib/rc_check.c4
-rw-r--r--src/modules/systemlib/rc_check.h2
-rw-r--r--src/systemcmds/mixer/mixer.cpp (renamed from src/systemcmds/mixer/mixer.c)55
-rw-r--r--src/systemcmds/mixer/module.mk2
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c4
-rw-r--r--src/systemcmds/tests/module.mk1
-rw-r--r--src/systemcmds/tests/test_mixer.cpp199
-rw-r--r--src/systemcmds/tests/tests.h5
-rw-r--r--src/systemcmds/tests/tests_main.c1
63 files changed, 2868 insertions, 720 deletions
diff --git a/Documentation/l1_control.odg b/Documentation/l1_control.odg
new file mode 100644
index 000000000..69910c677
--- /dev/null
+++ b/Documentation/l1_control.odg
Binary files differ
diff --git a/ROMFS/px4fmu_common/init.d/1000_rc_fw.hil b/ROMFS/px4fmu_common/init.d/1000_rc_fw.hil
index 6e29bd6f8..5e4028bbb 100644
--- a/ROMFS/px4fmu_common/init.d/1000_rc_fw.hil
+++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw.hil
@@ -33,6 +33,8 @@ then
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
param set SYS_AUTOCONFIG 0
param save
diff --git a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
new file mode 100644
index 000000000..1c85e04f2
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
@@ -0,0 +1,110 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILS quadrotor + starting.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.0
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.05
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 3.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.1
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.05
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.5
+ param set MPC_THR_MIN 0.1
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+# Allow USB some time to come up
+sleep 1
+# Tell MAVLink that this link is "fast"
+mavlink start -b 230400 -d /dev/ttyACM0
+
+# Create a fake HIL /dev/pwm_output interface
+hil mode_pwm
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 2
+
+#
+# Start the commander (depends on orb, mavlink)
+#
+commander start
+
+#
+# Check if we got an IO
+#
+if px4io start
+then
+ echo "IO started"
+else
+ fmu mode_serial
+ echo "FMU started"
+fi
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start the attitude estimator (depends on orb)
+#
+att_pos_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
index 828540ad9..4f843e9aa 100644
--- a/ROMFS/px4fmu_common/init.d/100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
@@ -29,6 +29,8 @@ then
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
param set SYS_AUTOCONFIG 0
param save
@@ -98,8 +100,7 @@ else
mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
fi
fw_att_control start
-# Not ready yet for prime-time
-#fw_pos_control_l1 start
+fw_pos_control_l1 start
if [ $EXIT_ON_END == yes ]
then
diff --git a/ROMFS/px4fmu_common/init.d/101_hk_bixler b/ROMFS/px4fmu_common/init.d/101_hk_bixler
index 5a9cb2171..cef86c34d 100644
--- a/ROMFS/px4fmu_common/init.d/101_hk_bixler
+++ b/ROMFS/px4fmu_common/init.d/101_hk_bixler
@@ -29,6 +29,8 @@ then
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
param set SYS_AUTOCONFIG 0
param save
@@ -91,8 +93,7 @@ att_pos_estimator_ekf start
#
mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
fw_att_control start
-# Not ready yet for prime-time
-#fw_pos_control_l1 start
+fw_pos_control_l1 start
if [ $EXIT_ON_END == yes ]
then
diff --git a/ROMFS/px4fmu_common/init.d/12-13_hex b/ROMFS/px4fmu_common/init.d/12-13_hex
new file mode 100644
index 000000000..0f0bb05ce
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/12-13_hex
@@ -0,0 +1,95 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on Hex"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
+# 13 = hexarotor
+#
+param set MAV_TYPE 13
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+ # Set PWM values for DJI ESCs
+ px4io idle 900 900 900 900 900 900
+ px4io min 1200 1200 1200 1200 1200 1200
+ px4io max 1900 1900 1900 1900 1900 1900
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output $MIXER
+
+#
+# Set PWM output frequency to 400 Hz
+#
+pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom
index 8fe94452f..652833745 100644
--- a/ROMFS/px4fmu_common/init.d/31_io_phantom
+++ b/ROMFS/px4fmu_common/init.d/31_io_phantom
@@ -29,6 +29,8 @@ then
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 17
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
param set SYS_AUTOCONFIG 0
param save
diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway
index 4b7ed5286..fb9dec043 100644
--- a/ROMFS/px4fmu_common/init.d/40_io_segway
+++ b/ROMFS/px4fmu_common/init.d/40_io_segway
@@ -52,5 +52,5 @@ attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
-md25 start 3 0x58
+roboclaw start /dev/ttyS2 128 1200
segway start
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
index e645d9d54..2bfaed76c 100644
--- a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
@@ -58,7 +58,7 @@ usleep 10000
if px4io detect
then
# Start MAVLink (depends on orb)
- mavlink start -d /dev/ttyS1 -b 115200
+ mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
sh /etc/init.d/rc.io
@@ -78,7 +78,7 @@ then
else
fmu mode_pwm
# Start MAVLink (on UART1 / ttyS0)
- mavlink start -d /dev/ttyS1 -b 115200
+ mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 93e76184d..424787d54 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -110,23 +110,33 @@ then
then
sh /etc/init.d/1000_rc_fw.hil
set MODE custom
- else
- if param compare SYS_AUTOSTART 1001
- then
- sh /etc/init.d/1001_rc_quad.hil
- set MODE custom
- else
- if param compare SYS_AUTOSTART 1002
- then
- sh /etc/init.d/1002_rc_fw_state.hil
- set MODE custom
- else
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
- fi
- fi
fi
+ if param compare SYS_AUTOSTART 1001
+ then
+ sh /etc/init.d/1001_rc_quad.hil
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 1002
+ then
+ sh /etc/init.d/1002_rc_fw_state.hil
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 1003
+ then
+ sh /etc/init.d/1003_rc_quad_+.hil
+ set MODE custom
+ fi
+
+ if [ $MODE != custom ]
+ then
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+ fi
+
+
#
# Upgrade PX4IO firmware
#
@@ -177,6 +187,20 @@ then
sh /etc/init.d/11_dji_f450
set MODE custom
fi
+
+ if param compare SYS_AUTOSTART 12
+ then
+ set MIXER /etc/mixers/FMU_hex_x.mix
+ sh /etc/init.d/12-13_hex
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 13
+ then
+ set MIXER /etc/mixers/FMU_hex_+.mix
+ sh /etc/init.d/12-13_hex
+ set MODE custom
+ fi
if param compare SYS_AUTOSTART 15
then
@@ -248,13 +272,19 @@ then
sh /etc/init.d/30_io_camflyer
set MODE custom
fi
-
+
if param compare SYS_AUTOSTART 31
then
sh /etc/init.d/31_io_phantom
set MODE custom
fi
+ if param compare SYS_AUTOSTART 40
+ then
+ sh /etc/init.d/40_io_segway
+ set MODE custom
+ fi
+
if param compare SYS_AUTOSTART 100
then
sh /etc/init.d/100_mpx_easystar
diff --git a/Tools/px4params/README.md b/Tools/px4params/README.md
new file mode 100644
index 000000000..a23b44799
--- /dev/null
+++ b/Tools/px4params/README.md
@@ -0,0 +1,9 @@
+h1. PX4 Parameters Processor
+
+It's designed to scan PX4 source codes, find declarations of tunable parameters,
+and generate the list in various formats.
+
+Currently supported formats are:
+
+* XML for the parametric UI generator
+* Human-readable description in DokuWiki format
diff --git a/Tools/px4params/dokuwikiout.py b/Tools/px4params/dokuwikiout.py
new file mode 100644
index 000000000..33f76b415
--- /dev/null
+++ b/Tools/px4params/dokuwikiout.py
@@ -0,0 +1,27 @@
+import output
+
+class DokuWikiOutput(output.Output):
+ def Generate(self, groups):
+ result = ""
+ for group in groups:
+ result += "==== %s ====\n\n" % group.GetName()
+ for param in group.GetParams():
+ code = param.GetFieldValue("code")
+ name = param.GetFieldValue("short_desc")
+ if code != name:
+ name = "%s (%s)" % (name, code)
+ result += "=== %s ===\n\n" % name
+ long_desc = param.GetFieldValue("long_desc")
+ if long_desc is not None:
+ result += "%s\n\n" % long_desc
+ min_val = param.GetFieldValue("min")
+ if min_val is not None:
+ result += "* Minimal value: %s\n" % min_val
+ max_val = param.GetFieldValue("max")
+ if max_val is not None:
+ result += "* Maximal value: %s\n" % max_val
+ def_val = param.GetFieldValue("default")
+ if def_val is not None:
+ result += "* Default value: %s\n" % def_val
+ result += "\n"
+ return result
diff --git a/Tools/px4params/output.py b/Tools/px4params/output.py
new file mode 100644
index 000000000..c09246871
--- /dev/null
+++ b/Tools/px4params/output.py
@@ -0,0 +1,5 @@
+class Output(object):
+ def Save(self, groups, fn):
+ data = self.Generate(groups)
+ with open(fn, 'w') as f:
+ f.write(data)
diff --git a/Tools/px4params/parser.py b/Tools/px4params/parser.py
new file mode 100644
index 000000000..251be672f
--- /dev/null
+++ b/Tools/px4params/parser.py
@@ -0,0 +1,220 @@
+import sys
+import re
+
+class ParameterGroup(object):
+ """
+ Single parameter group
+ """
+ def __init__(self, name):
+ self.name = name
+ self.params = []
+
+ def AddParameter(self, param):
+ """
+ Add parameter to the group
+ """
+ self.params.append(param)
+
+ def GetName(self):
+ """
+ Get parameter group name
+ """
+ return self.name
+
+ def GetParams(self):
+ """
+ Returns the parsed list of parameters. Every parameter is a Parameter
+ object. Note that returned object is not a copy. Modifications affect
+ state of the parser.
+ """
+ return sorted(self.params,
+ cmp=lambda x, y: cmp(x.GetFieldValue("code"),
+ y.GetFieldValue("code")))
+
+class Parameter(object):
+ """
+ Single parameter
+ """
+
+ # Define sorting order of the fields
+ priority = {
+ "code": 10,
+ "type": 9,
+ "short_desc": 8,
+ "long_desc": 7,
+ "default": 6,
+ "min": 5,
+ "max": 4,
+ # all others == 0 (sorted alphabetically)
+ }
+
+ def __init__(self):
+ self.fields = {}
+
+ def SetField(self, code, value):
+ """
+ Set named field value
+ """
+ self.fields[code] = value
+
+ def GetFieldCodes(self):
+ """
+ Return list of existing field codes in convenient order
+ """
+ return sorted(self.fields.keys(),
+ cmp=lambda x, y: cmp(self.priority.get(y, 0),
+ self.priority.get(x, 0)) or cmp(x, y))
+
+ def GetFieldValue(self, code):
+ """
+ Return value of the given field code or None if not found.
+ """
+ return self.fields.get(code)
+
+class Parser(object):
+ """
+ Parses provided data and stores all found parameters internally.
+ """
+
+ re_split_lines = re.compile(r'[\r\n]+')
+ re_comment_start = re.compile(r'^\/\*\*')
+ re_comment_content = re.compile(r'^\*\s*(.*)')
+ re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)')
+ re_comment_end = re.compile(r'(.*?)\s*\*\/')
+ re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;')
+ re_cut_type_specifier = re.compile(r'[a-z]+$')
+ re_is_a_number = re.compile(r'^-?[0-9\.]')
+ re_remove_dots = re.compile(r'\.+$')
+
+ valid_tags = set(["min", "max", "group"])
+
+ # Order of parameter groups
+ priority = {
+ # All other groups = 0 (sort alphabetically)
+ "Miscellaneous": -10
+ }
+
+ def __init__(self):
+ self.param_groups = {}
+
+ def GetSupportedExtensions(self):
+ """
+ Returns list of supported file extensions that can be parsed by this
+ parser.
+ """
+ return ["cpp", "c"]
+
+ def Parse(self, contents):
+ """
+ Incrementally parse program contents and append all found parameters
+ to the list.
+ """
+ # This code is essentially a comment-parsing grammar. "state"
+ # represents parser state. It contains human-readable state
+ # names.
+ state = None
+ for line in self.re_split_lines.split(contents):
+ line = line.strip()
+ # Ignore empty lines
+ if line == "":
+ continue
+ if self.re_comment_start.match(line):
+ state = "wait-short"
+ short_desc = None
+ long_desc = None
+ tags = {}
+ elif state is not None and state != "comment-processed":
+ m = self.re_comment_end.search(line)
+ if m:
+ line = m.group(1)
+ last_comment_line = True
+ else:
+ last_comment_line = False
+ m = self.re_comment_content.match(line)
+ if m:
+ comment_content = m.group(1)
+ if comment_content == "":
+ # When short comment ends with empty comment line,
+ # start waiting for the next part - long comment.
+ if state == "wait-short-end":
+ state = "wait-long"
+ else:
+ m = self.re_comment_tag.match(comment_content)
+ if m:
+ tag, desc = m.group(1, 2)
+ tags[tag] = desc
+ current_tag = tag
+ state = "wait-tag-end"
+ elif state == "wait-short":
+ # Store first line of the short description
+ short_desc = comment_content
+ state = "wait-short-end"
+ elif state == "wait-short-end":
+ # Append comment line to the short description
+ short_desc += "\n" + comment_content
+ elif state == "wait-long":
+ # Store first line of the long description
+ long_desc = comment_content
+ state = "wait-long-end"
+ elif state == "wait-long-end":
+ # Append comment line to the long description
+ long_desc += "\n" + comment_content
+ elif state == "wait-tag-end":
+ # Append comment line to the tag text
+ tags[current_tag] += "\n" + comment_content
+ else:
+ raise AssertionError(
+ "Invalid parser state: %s" % state)
+ elif not last_comment_line:
+ # Invalid comment line (inside comment, but not starting with
+ # "*" or "*/". Reset parsed content.
+ state = None
+ if last_comment_line:
+ state = "comment-processed"
+ else:
+ # Non-empty line outside the comment
+ m = self.re_parameter_definition.match(line)
+ if m:
+ tp, code, defval = m.group(1, 2, 3)
+ # Remove trailing type specifier from numbers: 0.1f => 0.1
+ if self.re_is_a_number.match(defval):
+ defval = self.re_cut_type_specifier.sub('', defval)
+ param = Parameter()
+ param.SetField("code", code)
+ param.SetField("short_desc", code)
+ param.SetField("type", tp)
+ param.SetField("default", defval)
+ # If comment was found before the parameter declaration,
+ # inject its data into the newly created parameter.
+ group = "Miscellaneous"
+ if state == "comment-processed":
+ if short_desc is not None:
+ param.SetField("short_desc",
+ self.re_remove_dots.sub('', short_desc))
+ if long_desc is not None:
+ param.SetField("long_desc", long_desc)
+ for tag in tags:
+ if tag == "group":
+ group = tags[tag]
+ elif tag not in self.valid_tags:
+ sys.stderr.write("Skipping invalid"
+ "documentation tag: '%s'\n" % tag)
+ else:
+ param.SetField(tag, tags[tag])
+ # Store the parameter
+ if group not in self.param_groups:
+ self.param_groups[group] = ParameterGroup(group)
+ self.param_groups[group].AddParameter(param)
+ # Reset parsed comment.
+ state = None
+
+ def GetParamGroups(self):
+ """
+ Returns the parsed list of parameters. Every parameter is a Parameter
+ object. Note that returned object is not a copy. Modifications affect
+ state of the parser.
+ """
+ return sorted(self.param_groups.values(),
+ cmp=lambda x, y: cmp(self.priority.get(y.GetName(), 0),
+ self.priority.get(x.GetName(), 0)) or cmp(x.GetName(),
+ y.GetName()))
diff --git a/Tools/px4params/px_process_params.py b/Tools/px4params/px_process_params.py
new file mode 100755
index 000000000..cdf5aba7c
--- /dev/null
+++ b/Tools/px4params/px_process_params.py
@@ -0,0 +1,61 @@
+#!/usr/bin/env python
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# PX4 paramers processor (main executable file)
+#
+# It scans src/ subdirectory of the project, collects all parameters
+# definitions, and outputs list of parameters in XML and DokuWiki formats.
+#
+
+import scanner
+import parser
+import xmlout
+import dokuwikiout
+
+# Initialize parser
+prs = parser.Parser()
+
+# Scan directories, and parse the files
+sc = scanner.Scanner()
+sc.ScanDir("../../src", prs)
+output = prs.GetParamGroups()
+
+# Output into XML
+out = xmlout.XMLOutput()
+out.Save(output, "parameters.xml")
+
+# Output into DokuWiki
+out = dokuwikiout.DokuWikiOutput()
+out.Save(output, "parameters.wiki")
diff --git a/Tools/px4params/scanner.py b/Tools/px4params/scanner.py
new file mode 100644
index 000000000..b5a1af47c
--- /dev/null
+++ b/Tools/px4params/scanner.py
@@ -0,0 +1,34 @@
+import os
+import re
+
+class Scanner(object):
+ """
+ Traverses directory tree, reads all source files, and passes their contents
+ to the Parser.
+ """
+
+ re_file_extension = re.compile(r'\.([^\.]+)$')
+
+ def ScanDir(self, srcdir, parser):
+ """
+ Scans provided path and passes all found contents to the parser using
+ parser.Parse method.
+ """
+ extensions = set(parser.GetSupportedExtensions())
+ for dirname, dirnames, filenames in os.walk(srcdir):
+ for filename in filenames:
+ m = self.re_file_extension.search(filename)
+ if m:
+ ext = m.group(1)
+ if ext in extensions:
+ path = os.path.join(dirname, filename)
+ self.ScanFile(path, parser)
+
+ def ScanFile(self, path, parser):
+ """
+ Scans provided file and passes its contents to the parser using
+ parser.Parse method.
+ """
+ with open(path, 'r') as f:
+ contents = f.read()
+ parser.Parse(contents)
diff --git a/Tools/px4params/xmlout.py b/Tools/px4params/xmlout.py
new file mode 100644
index 000000000..d56802b15
--- /dev/null
+++ b/Tools/px4params/xmlout.py
@@ -0,0 +1,22 @@
+import output
+from xml.dom.minidom import getDOMImplementation
+
+class XMLOutput(output.Output):
+ def Generate(self, groups):
+ impl = getDOMImplementation()
+ xml_document = impl.createDocument(None, "parameters", None)
+ xml_parameters = xml_document.documentElement
+ for group in groups:
+ xml_group = xml_document.createElement("group")
+ xml_group.setAttribute("name", group.GetName())
+ xml_parameters.appendChild(xml_group)
+ for param in group.GetParams():
+ xml_param = xml_document.createElement("parameter")
+ xml_group.appendChild(xml_param)
+ for code in param.GetFieldCodes():
+ value = param.GetFieldValue(code)
+ xml_field = xml_document.createElement(code)
+ xml_param.appendChild(xml_field)
+ xml_value = xml_document.createTextNode(value)
+ xml_field.appendChild(xml_value)
+ return xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8")
diff --git a/Tools/tests-host/.gitignore b/Tools/tests-host/.gitignore
new file mode 100644
index 000000000..61e091551
--- /dev/null
+++ b/Tools/tests-host/.gitignore
@@ -0,0 +1,2 @@
+./obj/*
+mixer_test
diff --git a/Tools/tests-host/Makefile b/Tools/tests-host/Makefile
new file mode 100644
index 000000000..97410ff47
--- /dev/null
+++ b/Tools/tests-host/Makefile
@@ -0,0 +1,39 @@
+
+CC=g++
+CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers -I../../src -D__EXPORT="" -Dnullptr="0"
+
+ODIR=obj
+LDIR =../lib
+
+LIBS=-lm
+
+#_DEPS = test.h
+#DEPS = $(patsubst %,$(IDIR)/%,$(_DEPS))
+
+_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o mixer.o mixer_group.o mixer_load.o
+OBJ = $(patsubst %,$(ODIR)/%,$(_OBJ))
+
+#$(DEPS)
+$(ODIR)/%.o: %.cpp
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+$(ODIR)/%.o: ../../src/systemcmds/tests/%.cpp
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+$(ODIR)/%.o: ../../src/modules/systemlib/%.cpp
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.cpp
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.c
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+#
+mixer_test: $(OBJ)
+ g++ -o $@ $^ $(CFLAGS) $(LIBS)
+
+.PHONY: clean
+
+clean:
+ rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ \ No newline at end of file
diff --git a/Tools/tests-host/arch/board/board.h b/Tools/tests-host/arch/board/board.h
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/Tools/tests-host/arch/board/board.h
diff --git a/Tools/tests-host/mixer_test.cpp b/Tools/tests-host/mixer_test.cpp
new file mode 100644
index 000000000..042322aad
--- /dev/null
+++ b/Tools/tests-host/mixer_test.cpp
@@ -0,0 +1,12 @@
+#include <systemlib/mixer/mixer.h>
+#include <systemlib/err.h>
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[]) {
+ warnx("Host execution started");
+
+ char* args[] = {argv[0], "../../ROMFS/px4fmu_common/mixers/IO_pass.mix",
+ "../../ROMFS/px4fmu_common/mixers/FMU_quad_w.mix"};
+
+ test_mixer(3, args);
+} \ No newline at end of file
diff --git a/Tools/tests-host/nuttx/config.h b/Tools/tests-host/nuttx/config.h
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/Tools/tests-host/nuttx/config.h
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 46640f3c5..f9061c110 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -33,7 +33,7 @@ MODULES += drivers/hott/hott_sensors
MODULES += drivers/blinkm
MODULES += drivers/rgbled
MODULES += drivers/mkblctrl
-MODULES += drivers/md25
+MODULES += drivers/roboclaw
MODULES += drivers/airspeed
MODULES += drivers/ets_airspeed
MODULES += drivers/meas_airspeed
@@ -79,7 +79,7 @@ MODULES += examples/flow_position_estimator
#
# Vehicle Control
#
-#MODULES += modules/segway # XXX needs state machine update
+MODULES += modules/segway
MODULES += modules/fw_pos_control_l1
MODULES += modules/fw_att_control
MODULES += modules/multirotor_att_control
@@ -115,6 +115,7 @@ MODULES += lib/mathlib/math/filter
MODULES += lib/ecl
MODULES += lib/external_lgpl
MODULES += lib/geo
+MODULES += lib/conversion
#
# Demo apps
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index bb589cb9f..ed2f2da5e 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -31,6 +31,7 @@ MODULES += drivers/hil
MODULES += drivers/hott/hott_telemetry
MODULES += drivers/hott/hott_sensors
MODULES += drivers/blinkm
+MODULES += drivers/roboclaw
MODULES += drivers/airspeed
MODULES += drivers/ets_airspeed
MODULES += drivers/meas_airspeed
@@ -77,7 +78,7 @@ MODULES += examples/flow_position_estimator
#
# Vehicle Control
#
-#MODULES += modules/segway # XXX needs state machine update
+MODULES += modules/segway
MODULES += modules/fw_pos_control_l1
MODULES += modules/fw_att_control
MODULES += modules/multirotor_att_control
@@ -111,6 +112,7 @@ MODULES += lib/mathlib/math/filter
MODULES += lib/ecl
MODULES += lib/external_lgpl
MODULES += lib/geo
+MODULES += lib/conversion
#
# Demo apps
diff --git a/mavlink/include/mavlink/v1.0/mavlink_conversions.h b/mavlink/include/mavlink/v1.0/mavlink_conversions.h
index d89363577..51afac87c 100644
--- a/mavlink/include/mavlink/v1.0/mavlink_conversions.h
+++ b/mavlink/include/mavlink/v1.0/mavlink_conversions.h
@@ -9,6 +9,10 @@
#endif
#include <math.h>
+#ifndef M_PI_2
+ #define M_PI_2 ((float)asin(1))
+#endif
+
/**
* @file mavlink_conversions.h
*
@@ -49,12 +53,12 @@ MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, flo
float phi, theta, psi;
theta = asin(-dcm[2][0]);
- if (fabs(theta - M_PI_2) < 1.0e-3f) {
+ if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f;
- psi = (atan2(dcm[1][2] - dcm[0][1],
+ psi = (atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1]) + phi);
- } else if (fabs(theta + M_PI_2) < 1.0e-3f) {
+ } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1] - phi);
@@ -128,4 +132,4 @@ MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, flo
dcm[2][2] = cosPhi * cosThe;
}
-#endif \ No newline at end of file
+#endif
diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h
index eff5e7349..8a4f68428 100644
--- a/src/drivers/drv_accel.h
+++ b/src/drivers/drv_accel.h
@@ -66,7 +66,7 @@ struct accel_report {
int16_t temperature_raw;
};
-/** accel scaling factors; Vout = (Vin * Vscale) + Voffset */
+/** accel scaling factors; Vout = Vscale * (Vin + Voffset) */
struct accel_scale {
float x_offset;
float x_scale;
diff --git a/src/drivers/rgbled/rgbled.cpp b/src/drivers/rgbled/rgbled.cpp
index fedff769b..727c86e02 100644
--- a/src/drivers/rgbled/rgbled.cpp
+++ b/src/drivers/rgbled/rgbled.cpp
@@ -103,6 +103,7 @@ private:
bool _running;
int _led_interval;
+ bool _should_run;
int _counter;
void set_color(rgbled_color_t ledcolor);
@@ -136,6 +137,7 @@ RGBLED::RGBLED(int bus, int rgbled) :
_brightness(1.0f),
_running(false),
_led_interval(0),
+ _should_run(false),
_counter(0)
{
memset(&_work, 0, sizeof(_work));
@@ -170,7 +172,20 @@ RGBLED::probe()
bool on, powersave;
uint8_t r, g, b;
- ret = get(on, powersave, r, g, b);
+ /**
+ this may look strange, but is needed. There is a serial
+ EEPROM (Microchip-24aa01) on the PX4FMU-v1 that responds to
+ a bunch of I2C addresses, including the 0x55 used by this
+ LED device. So we need to do enough operations to be sure
+ we are talking to the right device. These 3 operations seem
+ to be enough, as the 3rd one consistently fails if no
+ RGBLED is on the bus.
+ */
+ if ((ret=get(on, powersave, r, g, b)) != OK ||
+ (ret=send_led_enable(false) != OK) ||
+ (ret=send_led_enable(false) != OK)) {
+ return ret;
+ }
return ret;
}
@@ -248,6 +263,11 @@ RGBLED::led_trampoline(void *arg)
void
RGBLED::led()
{
+ if (!_should_run) {
+ _running = false;
+ return;
+ }
+
switch (_mode) {
case RGBLED_MODE_BLINK_SLOW:
case RGBLED_MODE_BLINK_NORMAL:
@@ -409,10 +429,10 @@ RGBLED::set_mode(rgbled_mode_t mode)
{
if (mode != _mode) {
_mode = mode;
- bool should_run = false;
switch (mode) {
case RGBLED_MODE_OFF:
+ _should_run = false;
send_led_enable(false);
break;
@@ -423,7 +443,7 @@ RGBLED::set_mode(rgbled_mode_t mode)
break;
case RGBLED_MODE_BLINK_SLOW:
- should_run = true;
+ _should_run = true;
_counter = 0;
_led_interval = 2000;
_brightness = 1.0f;
@@ -431,7 +451,7 @@ RGBLED::set_mode(rgbled_mode_t mode)
break;
case RGBLED_MODE_BLINK_NORMAL:
- should_run = true;
+ _should_run = true;
_counter = 0;
_led_interval = 500;
_brightness = 1.0f;
@@ -439,7 +459,7 @@ RGBLED::set_mode(rgbled_mode_t mode)
break;
case RGBLED_MODE_BLINK_FAST:
- should_run = true;
+ _should_run = true;
_counter = 0;
_led_interval = 100;
_brightness = 1.0f;
@@ -447,14 +467,14 @@ RGBLED::set_mode(rgbled_mode_t mode)
break;
case RGBLED_MODE_BREATHE:
- should_run = true;
+ _should_run = true;
_counter = 0;
_led_interval = 25;
send_led_enable(true);
break;
case RGBLED_MODE_PATTERN:
- should_run = true;
+ _should_run = true;
_counter = 0;
_brightness = 1.0f;
send_led_enable(true);
@@ -466,16 +486,11 @@ RGBLED::set_mode(rgbled_mode_t mode)
}
/* if it should run now, start the workq */
- if (should_run && !_running) {
+ if (_should_run && !_running) {
_running = true;
work_queue(LPWORK, &_work, (worker_t)&RGBLED::led_trampoline, this, 1);
}
- /* if it should stop, then cancel the workq */
- if (!should_run && _running) {
- _running = false;
- work_cancel(LPWORK, &_work);
- }
}
}
@@ -559,7 +574,7 @@ rgbled_main(int argc, char *argv[])
int ch;
/* jump over start/off/etc and look at options first */
- while ((ch = getopt(argc - 1, &argv[1], "a:b:")) != EOF) {
+ while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
switch (ch) {
case 'a':
rgbledadr = strtol(optarg, NULL, 0);
@@ -575,7 +590,12 @@ rgbled_main(int argc, char *argv[])
}
}
- const char *verb = argv[1];
+ if (optind >= argc) {
+ rgbled_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
int fd;
int ret;
@@ -596,6 +616,9 @@ rgbled_main(int argc, char *argv[])
if (g_rgbled == nullptr) {
// fall back to default bus
+ if (PX4_I2C_BUS_LED == PX4_I2C_BUS_EXPANSION) {
+ errx(1, "init failed");
+ }
i2cdevice = PX4_I2C_BUS_LED;
}
}
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
new file mode 100644
index 000000000..d65a9be36
--- /dev/null
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -0,0 +1,328 @@
+/****************************************************************************
+ *
+ * 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 RoboClaw.cpp
+ *
+ * RoboClaw Motor Driver
+ *
+ * references:
+ * http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
+ *
+ */
+
+#include "RoboClaw.hpp"
+#include <poll.h>
+#include <stdio.h>
+#include <math.h>
+#include <string.h>
+#include <fcntl.h>
+#include <termios.h>
+
+#include <systemlib/err.h>
+#include <arch/board/board.h>
+#include <mavlink/mavlink_log.h>
+
+#include <controllib/uorb/UOrbPublication.hpp>
+#include <uORB/topics/debug_key_value.h>
+#include <drivers/drv_hrt.h>
+
+uint8_t RoboClaw::checksum_mask = 0x7f;
+
+RoboClaw::RoboClaw(const char *deviceName, uint16_t address,
+ uint16_t pulsesPerRev):
+ _address(address),
+ _pulsesPerRev(pulsesPerRev),
+ _uart(0),
+ _controlPoll(),
+ _actuators(NULL, ORB_ID(actuator_controls_0), 20),
+ _motor1Position(0),
+ _motor1Speed(0),
+ _motor1Overflow(0),
+ _motor2Position(0),
+ _motor2Speed(0),
+ _motor2Overflow(0)
+{
+ // setup control polling
+ _controlPoll.fd = _actuators.getHandle();
+ _controlPoll.events = POLLIN;
+
+ // start serial port
+ _uart = open(deviceName, O_RDWR | O_NOCTTY);
+ if (_uart < 0) err(1, "could not open %s", deviceName);
+ int ret = 0;
+ struct termios uart_config;
+ ret = tcgetattr(_uart, &uart_config);
+ if (ret < 0) err (1, "failed to get attr");
+ uart_config.c_oflag &= ~ONLCR; // no CR for every LF
+ ret = cfsetispeed(&uart_config, B38400);
+ if (ret < 0) err (1, "failed to set input speed");
+ ret = cfsetospeed(&uart_config, B38400);
+ if (ret < 0) err (1, "failed to set output speed");
+ ret = tcsetattr(_uart, TCSANOW, &uart_config);
+ if (ret < 0) err (1, "failed to set attr");
+
+ // setup default settings, reset encoders
+ resetEncoders();
+}
+
+RoboClaw::~RoboClaw()
+{
+ setMotorDutyCycle(MOTOR_1, 0.0);
+ setMotorDutyCycle(MOTOR_2, 0.0);
+ close(_uart);
+}
+
+int RoboClaw::readEncoder(e_motor motor)
+{
+ uint16_t sum = 0;
+ if (motor == MOTOR_1) {
+ _sendCommand(CMD_READ_ENCODER_1, nullptr, 0, sum);
+ } else if (motor == MOTOR_2) {
+ _sendCommand(CMD_READ_ENCODER_2, nullptr, 0, sum);
+ }
+ uint8_t rbuf[50];
+ usleep(5000);
+ int nread = read(_uart, rbuf, 50);
+ if (nread < 6) {
+ printf("failed to read\n");
+ return -1;
+ }
+ //printf("received: \n");
+ //for (int i=0;i<nread;i++) {
+ //printf("%d\t", rbuf[i]);
+ //}
+ //printf("\n");
+ uint32_t count = 0;
+ uint8_t * countBytes = (uint8_t *)(&count);
+ countBytes[3] = rbuf[0];
+ countBytes[2] = rbuf[1];
+ countBytes[1] = rbuf[2];
+ countBytes[0] = rbuf[3];
+ uint8_t status = rbuf[4];
+ uint8_t checksum = rbuf[5];
+ uint8_t checksum_computed = (sum + _sumBytes(rbuf, 5)) &
+ checksum_mask;
+ // check if checksum is valid
+ if (checksum != checksum_computed) {
+ printf("checksum failed: expected %d got %d\n",
+ checksum, checksum_computed);
+ return -1;
+ }
+ int overFlow = 0;
+
+ if (status & STATUS_REVERSE) {
+ //printf("roboclaw: reverse\n");
+ }
+
+ if (status & STATUS_UNDERFLOW) {
+ //printf("roboclaw: underflow\n");
+ overFlow = -1;
+ } else if (status & STATUS_OVERFLOW) {
+ //printf("roboclaw: overflow\n");
+ overFlow = +1;
+ }
+
+ static int64_t overflowAmount = 0x100000000LL;
+ if (motor == MOTOR_1) {
+ _motor1Overflow += overFlow;
+ _motor1Position = float(int64_t(count) +
+ _motor1Overflow*overflowAmount)/_pulsesPerRev;
+ } else if (motor == MOTOR_2) {
+ _motor2Overflow += overFlow;
+ _motor2Position = float(int64_t(count) +
+ _motor2Overflow*overflowAmount)/_pulsesPerRev;
+ }
+ return 0;
+}
+
+void RoboClaw::printStatus(char *string, size_t n)
+{
+ snprintf(string, n,
+ "pos1,spd1,pos2,spd2: %10.2f %10.2f %10.2f %10.2f\n",
+ double(getMotorPosition(MOTOR_1)),
+ double(getMotorSpeed(MOTOR_1)),
+ double(getMotorPosition(MOTOR_2)),
+ double(getMotorSpeed(MOTOR_2)));
+}
+
+float RoboClaw::getMotorPosition(e_motor motor)
+{
+ if (motor == MOTOR_1) {
+ return _motor1Position;
+ } else if (motor == MOTOR_2) {
+ return _motor2Position;
+ }
+}
+
+float RoboClaw::getMotorSpeed(e_motor motor)
+{
+ if (motor == MOTOR_1) {
+ return _motor1Speed;
+ } else if (motor == MOTOR_2) {
+ return _motor2Speed;
+ }
+}
+
+int RoboClaw::setMotorSpeed(e_motor motor, float value)
+{
+ uint16_t sum = 0;
+ // bound
+ if (value > 1) value = 1;
+ if (value < -1) value = -1;
+ uint8_t speed = fabs(value)*127;
+ // send command
+ if (motor == MOTOR_1) {
+ if (value > 0) {
+ return _sendCommand(CMD_DRIVE_FWD_1, &speed, 1, sum);
+ } else {
+ return _sendCommand(CMD_DRIVE_REV_1, &speed, 1, sum);
+ }
+ } else if (motor == MOTOR_2) {
+ if (value > 0) {
+ return _sendCommand(CMD_DRIVE_FWD_2, &speed, 1, sum);
+ } else {
+ return _sendCommand(CMD_DRIVE_REV_2, &speed, 1, sum);
+ }
+ }
+ return -1;
+}
+
+int RoboClaw::setMotorDutyCycle(e_motor motor, float value)
+{
+ uint16_t sum = 0;
+ // bound
+ if (value > 1) value = 1;
+ if (value < -1) value = -1;
+ int16_t duty = 1500*value;
+ // send command
+ if (motor == MOTOR_1) {
+ return _sendCommand(CMD_SIGNED_DUTYCYCLE_1,
+ (uint8_t *)(&duty), 2, sum);
+ } else if (motor == MOTOR_2) {
+ return _sendCommand(CMD_SIGNED_DUTYCYCLE_2,
+ (uint8_t *)(&duty), 2, sum);
+ }
+ return -1;
+}
+
+int RoboClaw::resetEncoders()
+{
+ uint16_t sum = 0;
+ return _sendCommand(CMD_RESET_ENCODERS,
+ nullptr, 0, sum);
+}
+
+int RoboClaw::update()
+{
+ // wait for an actuator publication,
+ // check for exit condition every second
+ // note "::poll" is required to distinguish global
+ // poll from member function for driver
+ if (::poll(&_controlPoll, 1, 1000) < 0) return -1; // poll error
+
+ // if new data, send to motors
+ if (_actuators.updated()) {
+ _actuators.update();
+ setMotorDutyCycle(MOTOR_1,_actuators.control[CH_VOLTAGE_LEFT]);
+ setMotorDutyCycle(MOTOR_2,_actuators.control[CH_VOLTAGE_RIGHT]);
+ }
+ return 0;
+}
+
+uint16_t RoboClaw::_sumBytes(uint8_t * buf, size_t n)
+{
+ uint16_t sum = 0;
+ //printf("sum\n");
+ for (size_t i=0;i<n;i++) {
+ sum += buf[i];
+ //printf("%d\t", buf[i]);
+ }
+ //printf("total sum %d\n", sum);
+ return sum;
+}
+
+int RoboClaw::_sendCommand(e_command cmd, uint8_t * data,
+ size_t n_data, uint16_t & prev_sum)
+{
+ tcflush(_uart, TCIOFLUSH); // flush buffers
+ uint8_t buf[n_data + 3];
+ buf[0] = _address;
+ buf[1] = cmd;
+ for (size_t i=0;i<n_data;i++) {
+ buf[i+2] = data[n_data - i - 1]; // MSB
+ }
+ uint16_t sum = _sumBytes(buf, n_data + 2);
+ prev_sum += sum;
+ buf[n_data + 2] = sum & checksum_mask;
+ //printf("\nmessage:\n");
+ //for (size_t i=0;i<n_data+3;i++) {
+ //printf("%d\t", buf[i]);
+ //}
+ //printf("\n");
+ return write(_uart, buf, n_data + 3);
+}
+
+int roboclawTest(const char *deviceName, uint8_t address,
+ uint16_t pulsesPerRev)
+{
+ printf("roboclaw test: starting\n");
+
+ // setup
+ RoboClaw roboclaw(deviceName, address, pulsesPerRev);
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_1, 0.3);
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_2, 0.3);
+ char buf[200];
+ for (int i=0; i<10; i++) {
+ usleep(100000);
+ roboclaw.readEncoder(RoboClaw::MOTOR_1);
+ roboclaw.readEncoder(RoboClaw::MOTOR_2);
+ roboclaw.printStatus(buf,200);
+ printf("%s", buf);
+ }
+
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_1, -0.3);
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_2, -0.3);
+ for (int i=0; i<10; i++) {
+ usleep(100000);
+ roboclaw.readEncoder(RoboClaw::MOTOR_1);
+ roboclaw.readEncoder(RoboClaw::MOTOR_2);
+ roboclaw.printStatus(buf,200);
+ printf("%s", buf);
+ }
+
+ printf("Test complete\n");
+ return 0;
+}
+
+// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/roboclaw/RoboClaw.hpp b/src/drivers/roboclaw/RoboClaw.hpp
new file mode 100644
index 000000000..e9f35cf95
--- /dev/null
+++ b/src/drivers/roboclaw/RoboClaw.hpp
@@ -0,0 +1,192 @@
+/****************************************************************************
+ *
+ * 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 RoboClas.hpp
+ *
+ * RoboClaw Motor Driver
+ *
+ * references:
+ * http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
+ *
+ */
+
+#pragma once
+
+#include <poll.h>
+#include <stdio.h>
+#include <controllib/uorb/UOrbSubscription.hpp>
+#include <uORB/topics/actuator_controls.h>
+#include <drivers/device/i2c.h>
+
+/**
+ * This is a driver for the RoboClaw motor controller
+ */
+class RoboClaw
+{
+public:
+
+ /** control channels */
+ enum e_channel {
+ CH_VOLTAGE_LEFT = 0,
+ CH_VOLTAGE_RIGHT
+ };
+
+ /** motors */
+ enum e_motor {
+ MOTOR_1 = 0,
+ MOTOR_2
+ };
+
+ /**
+ * constructor
+ * @param deviceName the name of the
+ * serial port e.g. "/dev/ttyS2"
+ * @param address the adddress of the motor
+ * (selectable on roboclaw)
+ * @param pulsesPerRev # of encoder
+ * pulses per revolution of wheel
+ */
+ RoboClaw(const char *deviceName, uint16_t address,
+ uint16_t pulsesPerRev);
+
+ /**
+ * deconstructor
+ */
+ virtual ~RoboClaw();
+
+ /**
+ * @return position of a motor, rev
+ */
+ float getMotorPosition(e_motor motor);
+
+ /**
+ * @return speed of a motor, rev/sec
+ */
+ float getMotorSpeed(e_motor motor);
+
+ /**
+ * set the speed of a motor, rev/sec
+ */
+ int setMotorSpeed(e_motor motor, float value);
+
+ /**
+ * set the duty cycle of a motor, rev/sec
+ */
+ int setMotorDutyCycle(e_motor motor, float value);
+
+ /**
+ * reset the encoders
+ * @return status
+ */
+ int resetEncoders();
+
+ /**
+ * main update loop that updates RoboClaw motor
+ * dutycycle based on actuator publication
+ */
+ int update();
+
+ /**
+ * read data from serial
+ */
+ int readEncoder(e_motor motor);
+
+ /**
+ * print status
+ */
+ void printStatus(char *string, size_t n);
+
+private:
+
+ // Quadrature status flags
+ enum e_quadrature_status_flags {
+ STATUS_UNDERFLOW = 1 << 0, /**< encoder went below 0 **/
+ STATUS_REVERSE = 1 << 1, /**< motor doing in reverse dir **/
+ STATUS_OVERFLOW = 1 << 2, /**< encoder went above 2^32 **/
+ };
+
+ // commands
+ // We just list the commands we want from the manual here.
+ enum e_command {
+
+ // simple
+ CMD_DRIVE_FWD_1 = 0,
+ CMD_DRIVE_REV_1 = 1,
+ CMD_DRIVE_FWD_2 = 4,
+ CMD_DRIVE_REV_2 = 5,
+
+ // encoder commands
+ CMD_READ_ENCODER_1 = 16,
+ CMD_READ_ENCODER_2 = 17,
+ CMD_RESET_ENCODERS = 20,
+
+ // advanced motor control
+ CMD_READ_SPEED_HIRES_1 = 30,
+ CMD_READ_SPEED_HIRES_2 = 31,
+ CMD_SIGNED_DUTYCYCLE_1 = 32,
+ CMD_SIGNED_DUTYCYCLE_2 = 33,
+ };
+
+ static uint8_t checksum_mask;
+
+ uint16_t _address;
+ uint16_t _pulsesPerRev;
+
+ int _uart;
+
+ /** poll structure for control packets */
+ struct pollfd _controlPoll;
+
+ /** actuator controls subscription */
+ control::UOrbSubscription<actuator_controls_s> _actuators;
+
+ // private data
+ float _motor1Position;
+ float _motor1Speed;
+ int16_t _motor1Overflow;
+
+ float _motor2Position;
+ float _motor2Speed;
+ int16_t _motor2Overflow;
+
+ // private methods
+ uint16_t _sumBytes(uint8_t * buf, size_t n);
+ int _sendCommand(e_command cmd, uint8_t * data, size_t n_data, uint16_t & prev_sum);
+};
+
+// unit testing
+int roboclawTest(const char *deviceName, uint8_t address,
+ uint16_t pulsesPerRev);
+
+// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/roboclaw/module.mk b/src/drivers/roboclaw/module.mk
new file mode 100644
index 000000000..1abecf198
--- /dev/null
+++ b/src/drivers/roboclaw/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# RoboClaw Motor Controller
+#
+
+MODULE_COMMAND = roboclaw
+
+SRCS = roboclaw_main.cpp \
+ RoboClaw.cpp
diff --git a/src/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp
new file mode 100644
index 000000000..44ed03254
--- /dev/null
+++ b/src/drivers/roboclaw/roboclaw_main.cpp
@@ -0,0 +1,195 @@
+/****************************************************************************
+ *
+ * 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 roboclaw_main.cpp
+ *
+ * RoboClaw Motor Driver
+ *
+ * references:
+ * http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
+ *
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <math.h>
+
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+
+#include <arch/board/board.h>
+#include "RoboClaw.hpp"
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int deamon_task; /**< Handle of deamon task / thread */
+
+/**
+ * Deamon management function.
+ */
+extern "C" __EXPORT int roboclaw_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of deamon.
+ */
+int roboclaw_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage();
+
+static void usage()
+{
+ fprintf(stderr, "usage: roboclaw "
+ "{start|stop|status|test}\n\n");
+}
+
+/**
+ * The deamon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int roboclaw_main(int argc, char *argv[])
+{
+
+ if (argc < 1)
+ usage();
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ printf("roboclaw already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ deamon_task = task_spawn_cmd("roboclaw",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 10,
+ 2048,
+ roboclaw_thread_main,
+ (const char **)argv);
+ exit(0);
+
+ } else if (!strcmp(argv[1], "test")) {
+
+ const char * deviceName = "/dev/ttyS2";
+ uint8_t address = 128;
+ uint16_t pulsesPerRev = 1200;
+
+ if (argc == 2) {
+ printf("testing with default settings\n");
+ } else if (argc != 4) {
+ printf("usage: roboclaw test device address pulses_per_rev\n");
+ exit(-1);
+ } else {
+ deviceName = argv[2];
+ address = strtoul(argv[3], nullptr, 0);
+ pulsesPerRev = strtoul(argv[4], nullptr, 0);
+ }
+
+ printf("device:\t%s\taddress:\t%d\tpulses per rev:\t%ld\n",
+ deviceName, address, pulsesPerRev);
+
+ roboclawTest(deviceName, address, pulsesPerRev);
+ thread_should_exit = true;
+ exit(0);
+
+ } else if (!strcmp(argv[1], "stop")) {
+
+ thread_should_exit = true;
+ exit(0);
+
+ } else if (!strcmp(argv[1], "status")) {
+
+ if (thread_running) {
+ printf("\troboclaw app is running\n");
+
+ } else {
+ printf("\troboclaw app not started\n");
+ }
+ exit(0);
+ }
+
+ usage();
+ exit(1);
+}
+
+int roboclaw_thread_main(int argc, char *argv[])
+{
+ printf("[roboclaw] starting\n");
+
+ // skip parent process args
+ argc -=2;
+ argv +=2;
+
+ if (argc < 3) {
+ printf("usage: roboclaw start device address\n");
+ return -1;
+ }
+
+ const char *deviceName = argv[1];
+ uint8_t address = strtoul(argv[2], nullptr, 0);
+ uint16_t pulsesPerRev = strtoul(argv[3], nullptr, 0);
+
+ printf("device:\t%s\taddress:\t%d\tpulses per rev:\t%ld\n",
+ deviceName, address, pulsesPerRev);
+
+ // start
+ RoboClaw roboclaw(deviceName, address, pulsesPerRev);
+
+ thread_running = true;
+
+ // loop
+ while (!thread_should_exit) {
+ roboclaw.update();
+ }
+
+ // exit
+ printf("[roboclaw] exiting.\n");
+ thread_running = false;
+ return 0;
+}
+
+// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/lib/conversion/module.mk b/src/lib/conversion/module.mk
new file mode 100644
index 000000000..f5f59a2dc
--- /dev/null
+++ b/src/lib/conversion/module.mk
@@ -0,0 +1,38 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Conversion library
+#
+
+SRCS = rotation.cpp
diff --git a/src/lib/conversion/rotation.cpp b/src/lib/conversion/rotation.cpp
new file mode 100644
index 000000000..b078562c2
--- /dev/null
+++ b/src/lib/conversion/rotation.cpp
@@ -0,0 +1,62 @@
+/****************************************************************************
+ *
+ * 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 rotation.cpp
+ *
+ * Vector rotation library
+ */
+
+#include "math.h"
+#include "rotation.h"
+
+__EXPORT void
+get_rot_matrix(enum Rotation rot, math::Matrix *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);
+ }
+ }
+}
diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h
new file mode 100644
index 000000000..85c63c0fc
--- /dev/null
+++ b/src/lib/conversion/rotation.h
@@ -0,0 +1,121 @@
+/****************************************************************************
+ *
+ * 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 rotation.h
+ *
+ * Vector rotation library
+ */
+
+#ifndef ROTATION_H_
+#define ROTATION_H_
+
+#include <unistd.h>
+#include <mathlib/mathlib.h>
+
+/**
+ * Enum for board and external compass rotations.
+ * This enum maps from board attitude to airframe attitude.
+ */
+enum Rotation {
+ ROTATION_NONE = 0,
+ ROTATION_YAW_45 = 1,
+ ROTATION_YAW_90 = 2,
+ ROTATION_YAW_135 = 3,
+ ROTATION_YAW_180 = 4,
+ ROTATION_YAW_225 = 5,
+ ROTATION_YAW_270 = 6,
+ ROTATION_YAW_315 = 7,
+ ROTATION_ROLL_180 = 8,
+ ROTATION_ROLL_180_YAW_45 = 9,
+ ROTATION_ROLL_180_YAW_90 = 10,
+ ROTATION_ROLL_180_YAW_135 = 11,
+ ROTATION_PITCH_180 = 12,
+ ROTATION_ROLL_180_YAW_225 = 13,
+ ROTATION_ROLL_180_YAW_270 = 14,
+ ROTATION_ROLL_180_YAW_315 = 15,
+ ROTATION_ROLL_90 = 16,
+ ROTATION_ROLL_90_YAW_45 = 17,
+ ROTATION_ROLL_90_YAW_90 = 18,
+ ROTATION_ROLL_90_YAW_135 = 19,
+ ROTATION_ROLL_270 = 20,
+ ROTATION_ROLL_270_YAW_45 = 21,
+ ROTATION_ROLL_270_YAW_90 = 22,
+ ROTATION_ROLL_270_YAW_135 = 23,
+ ROTATION_PITCH_90 = 24,
+ ROTATION_PITCH_270 = 25,
+ ROTATION_MAX
+};
+
+typedef struct {
+ uint16_t roll;
+ uint16_t pitch;
+ uint16_t yaw;
+} rot_lookup_t;
+
+const rot_lookup_t rot_lookup[] = {
+ { 0, 0, 0 },
+ { 0, 0, 45 },
+ { 0, 0, 90 },
+ { 0, 0, 135 },
+ { 0, 0, 180 },
+ { 0, 0, 225 },
+ { 0, 0, 270 },
+ { 0, 0, 315 },
+ {180, 0, 0 },
+ {180, 0, 45 },
+ {180, 0, 90 },
+ {180, 0, 135 },
+ { 0, 180, 0 },
+ {180, 0, 225 },
+ {180, 0, 270 },
+ {180, 0, 315 },
+ { 90, 0, 0 },
+ { 90, 0, 45 },
+ { 90, 0, 90 },
+ { 90, 0, 135 },
+ {270, 0, 0 },
+ {270, 0, 45 },
+ {270, 0, 90 },
+ {270, 0, 135 },
+ { 0, 90, 0 },
+ { 0, 270, 0 }
+};
+
+/**
+ * Get the rotation matrix
+ */
+__EXPORT void
+get_rot_matrix(enum Rotation rot, math::Matrix *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 c5c0c7a3c..daf136d49 100644
--- a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
@@ -130,8 +130,12 @@ 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_airplane_unit = get_local_planar_vector(vector_B, vector_curr_position).normalized();
- float bearing_wp_b = atan2f(-vector_B_to_airplane_unit.getY() , -vector_B_to_airplane_unit.getX());
+ math::Vector2f vector_B_to_P_unit = get_local_planar_vector(vector_B, vector_curr_position).normalized();
+
+ /* calculate angle of airplane position vector relative to line) */
+
+ // XXX this could probably also be based solely on the dot product
+ float AB_to_BP_bearing = atan2f(vector_B_to_P_unit % vector_AB, vector_B_to_P_unit * vector_AB);
/* extension from [2], fly directly to A */
if (distance_A_to_airplane > _L1_distance && alongTrackDist / math::max(distance_A_to_airplane , 1.0f) < -0.7071f) {
@@ -148,21 +152,30 @@ void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, c
/* bearing from current position to L1 point */
_nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
-// XXX this can be useful as last-resort guard, but is currently not needed
-#if 0
- } else if (absf(bearing_wp_b) > math::radians(80.0f)) {
- /* extension, fly back to waypoint */
+ /*
+ * If the AB vector and the vector from B to airplane point in the same
+ * direction, we have missed the waypoint. At +- 90 degrees we are just passing it.
+ */
+ } else if (fabsf(AB_to_BP_bearing) < math::radians(100.0f)) {
+ /*
+ * Extension, fly back to waypoint.
+ *
+ * This corner case is possible if the system was following
+ * the AB line from waypoint A to waypoint B, then is
+ * switched to manual mode (or otherwise misses the waypoint)
+ * and behind the waypoint continues to follow the AB line.
+ */
/* calculate eta to fly to waypoint B */
/* velocity across / orthogonal to line */
- xtrack_vel = ground_speed_vector % (-vector_B_to_airplane_unit);
+ xtrack_vel = ground_speed_vector % (-vector_B_to_P_unit);
/* velocity along line */
- ltrack_vel = ground_speed_vector * (-vector_B_to_airplane_unit);
+ 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 = bearing_wp_b;
-#endif
+ _nav_bearing = atan2f(-vector_B_to_P_unit.getY() , -vector_B_to_P_unit.getX());
+
} else {
/* calculate eta to fly along the line between A and B */
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index cfa7d9e8a..5eeca5a1a 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -100,10 +100,29 @@
* accel_T = A^-1 * g
* g = 9.80665
*
+ * ===== Rotation =====
+ *
+ * Calibrating using model:
+ * accel_corr = accel_T_r * (rot * accel_raw - accel_offs_r)
+ *
+ * Actual correction:
+ * accel_corr = rot * accel_T * (accel_raw - accel_offs)
+ *
+ * Known: accel_T_r, accel_offs_r, rot
+ * Unknown: accel_T, accel_offs
+ *
+ * Solution:
+ * accel_T_r * (rot * accel_raw - accel_offs_r) = rot * accel_T * (accel_raw - accel_offs)
+ * rot^-1 * accel_T_r * (rot * accel_raw - accel_offs_r) = accel_T * (accel_raw - accel_offs)
+ * rot^-1 * accel_T_r * rot * accel_raw - rot^-1 * accel_T_r * accel_offs_r = accel_T * accel_raw - accel_T * accel_offs)
+ * => accel_T = rot^-1 * accel_T_r * rot
+ * => accel_offs = rot^-1 * accel_offs_r
+ *
* @author Anton Babushkin <anton.babushkin@me.com>
*/
#include "accelerometer_calibration.h"
+#include "calibration_messages.h"
#include "commander_helper.h"
#include <unistd.h>
@@ -112,11 +131,13 @@
#include <fcntl.h>
#include <sys/prctl.h>
#include <math.h>
+#include <mathlib/mathlib.h>
#include <string.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_combined.h>
#include <drivers/drv_accel.h>
#include <geo/geo.h>
+#include <conversion/rotation.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <mavlink/mavlink_log.h>
@@ -127,93 +148,122 @@
#endif
static const int ERROR = -1;
-int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]);
+static const char *sensor_name = "accel";
+
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_T[3][3]);
int detect_orientation(int mavlink_fd, int sub_sensor_combined);
int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num);
int mat_invert3(float src[3][3], float dst[3][3]);
int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g);
-int do_accel_calibration(int mavlink_fd) {
- /* announce change */
- mavlink_log_info(mavlink_fd, "accel calibration started");
- mavlink_log_info(mavlink_fd, "accel cal progress <0> percent");
+int do_accel_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+
+ struct accel_scale accel_scale = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ int res = OK;
+
+ /* reset all offsets to zero and all scales to one */
+ int fd = open(ACCEL_DEVICE_PATH, 0);
+ res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
+ close(fd);
+
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
- /* measure and calculate offsets & scales */
float accel_offs[3];
- float accel_scale[3];
- int res = do_accel_calibration_measurements(mavlink_fd, accel_offs, accel_scale);
+ float accel_T[3][3];
if (res == OK) {
- /* measurements complete successfully, set parameters */
- if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs[0]))
- || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs[1]))
- || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs[2]))
- || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0]))
- || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1]))
- || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) {
- mavlink_log_critical(mavlink_fd, "ERROR: setting offs or scale failed");
+ /* measure and calculate offsets & scales */
+ res = do_accel_calibration_measurements(mavlink_fd, accel_offs, accel_T);
+ }
+
+ if (res == OK) {
+ /* measurements completed successfully, rotate calibration values */
+ param_t board_rotation_h = param_find("SENS_BOARD_ROT");
+ int32_t board_rotation_int;
+ param_get(board_rotation_h, &(board_rotation_int));
+ enum Rotation board_rotation_id = (enum Rotation)board_rotation_int;
+ math::Matrix board_rotation(3, 3);
+ get_rot_matrix(board_rotation_id, &board_rotation);
+ math::Matrix board_rotation_t = board_rotation.transpose();
+ math::Vector3 accel_offs_vec;
+ accel_offs_vec.set(&accel_offs[0]);
+ math::Vector3 accel_offs_rotated = board_rotation_t * accel_offs_vec;
+ math::Matrix accel_T_mat(3, 3);
+ accel_T_mat.set(&accel_T[0][0]);
+ math::Matrix accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation;
+
+ accel_scale.x_offset = accel_offs_rotated(0);
+ accel_scale.x_scale = accel_T_rotated(0, 0);
+ accel_scale.y_offset = accel_offs_rotated(1);
+ accel_scale.y_scale = accel_T_rotated(1, 1);
+ accel_scale.z_offset = accel_offs_rotated(2);
+ accel_scale.z_scale = accel_T_rotated(2, 2);
+
+ /* set parameters */
+ if (param_set(param_find("SENS_ACC_XOFF"), &(accel_scale.x_offset))
+ || param_set(param_find("SENS_ACC_YOFF"), &(accel_scale.y_offset))
+ || param_set(param_find("SENS_ACC_ZOFF"), &(accel_scale.z_offset))
+ || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale.x_scale))
+ || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale.y_scale))
+ || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale.z_scale))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ res = ERROR;
}
+ }
+ if (res == OK) {
+ /* apply new scaling and offsets */
int fd = open(ACCEL_DEVICE_PATH, 0);
- struct accel_scale ascale = {
- accel_offs[0],
- accel_scale[0],
- accel_offs[1],
- accel_scale[1],
- accel_offs[2],
- accel_scale[2],
- };
-
- if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale))
- warn("WARNING: failed to set scale / offsets for accel");
-
+ res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
+ }
+
+ if (res == OK) {
/* auto-save to EEPROM */
- int save_ret = param_save_default();
+ res = param_save_default();
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
}
+ }
+
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- mavlink_log_info(mavlink_fd, "accel calibration done");
- return OK;
} else {
- /* measurements error */
- mavlink_log_info(mavlink_fd, "accel calibration aborted");
- return ERROR;
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
- /* exit accel calibration mode */
+ return res;
}
-int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) {
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_T[3][3])
+{
const int samples_num = 2500;
float accel_ref[6][3];
bool data_collected[6] = { false, false, false, false, false, false };
const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" };
- /* reset existing calibration */
- int fd = open(ACCEL_DEVICE_PATH, 0);
- struct accel_scale ascale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
- int ioctl_res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale_null);
- close(fd);
-
- if (OK != ioctl_res) {
- warn("ERROR: failed to set scale / offsets for accel");
- return ERROR;
- }
-
int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
unsigned done_count = 0;
+ int res = OK;
while (true) {
bool done = true;
@@ -221,64 +271,63 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
done_count = 0;
for (int i = 0; i < 6; i++) {
- if (!data_collected[i]) {
+ if (data_collected[i]) {
+ done_count++;
+
+ } else {
done = false;
}
}
- mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
- (!data_collected[0]) ? "x+ " : "",
- (!data_collected[1]) ? "x- " : "",
- (!data_collected[2]) ? "y+ " : "",
- (!data_collected[3]) ? "y- " : "",
- (!data_collected[4]) ? "z+ " : "",
- (!data_collected[5]) ? "z- " : "");
-
if (old_done_count != done_count)
- mavlink_log_info(mavlink_fd, "accel cal progress <%u> percent", 17 * done_count);
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
if (done)
break;
+ mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
+ (!data_collected[0]) ? "x+ " : "",
+ (!data_collected[1]) ? "x- " : "",
+ (!data_collected[2]) ? "y+ " : "",
+ (!data_collected[3]) ? "y- " : "",
+ (!data_collected[4]) ? "z+ " : "",
+ (!data_collected[5]) ? "z- " : "");
+
int orient = detect_orientation(mavlink_fd, sensor_combined_sub);
+
if (orient < 0) {
- close(sensor_combined_sub);
- return ERROR;
+ res = ERROR;
+ break;
}
if (data_collected[orient]) {
- mavlink_log_info(mavlink_fd, "%s done, please rotate to a different axis", orientation_strs[orient]);
+ mavlink_log_info(mavlink_fd, "%s done, rotate to a different axis", orientation_strs[orient]);
continue;
}
mavlink_log_info(mavlink_fd, "accel measurement started: %s axis", orientation_strs[orient]);
read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num);
mavlink_log_info(mavlink_fd, "result for %s axis: [ %.2f %.2f %.2f ]", orientation_strs[orient],
- (double)accel_ref[orient][0],
- (double)accel_ref[orient][1],
- (double)accel_ref[orient][2]);
+ (double)accel_ref[orient][0],
+ (double)accel_ref[orient][1],
+ (double)accel_ref[orient][2]);
data_collected[orient] = true;
tune_neutral();
}
+
close(sensor_combined_sub);
- /* calculate offsets and rotation+scale matrix */
- float accel_T[3][3];
- int res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G);
- if (res != 0) {
- mavlink_log_info(mavlink_fd, "ERROR: calibration values calculation error");
- return ERROR;
- }
+ if (res == OK) {
+ /* calculate offsets and transform matrix */
+ res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G);
- /* convert accel transform matrix to scales,
- * rotation part of transform matrix is not used by now
- */
- for (int i = 0; i < 3; i++) {
- accel_scale[i] = accel_T[i][i];
+ if (res != OK) {
+ mavlink_log_info(mavlink_fd, "ERROR: calibration values calculation error");
+ }
}
- return OK;
+ return res;
}
/*
@@ -287,14 +336,15 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
* @return 0..5 according to orientation when vehicle is still and ready for measurements,
* ERROR if vehicle is not still after 30s or orientation error is more than 5m/s^2
*/
-int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
+int detect_orientation(int mavlink_fd, int sub_sensor_combined)
+{
struct sensor_combined_s sensor;
/* exponential moving average of accel */
float accel_ema[3] = { 0.0f, 0.0f, 0.0f };
/* max-hold dispersion of accel */
float accel_disp[3] = { 0.0f, 0.0f, 0.0f };
/* EMA time constant in seconds*/
- float ema_len = 0.2f;
+ float ema_len = 0.5f;
/* set "still" threshold to 0.25 m/s^2 */
float still_thr2 = pow(0.25f, 2);
/* set accel error threshold to 5m/s^2 */
@@ -318,30 +368,38 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
while (true) {
/* wait blocking for new data */
int poll_ret = poll(fds, 1, 1000);
+
if (poll_ret) {
orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &sensor);
t = hrt_absolute_time();
float dt = (t - t_prev) / 1000000.0f;
t_prev = t;
float w = dt / ema_len;
+
for (int i = 0; i < 3; i++) {
- accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_m_s2[i] * w;
- float d = (float) sensor.accelerometer_m_s2[i] - accel_ema[i];
+ float d = sensor.accelerometer_m_s2[i] - accel_ema[i];
+ accel_ema[i] += d * w;
d = d * d;
accel_disp[i] = accel_disp[i] * (1.0f - w);
+
+ if (d > still_thr2 * 8.0f)
+ d = still_thr2 * 8.0f;
+
if (d > accel_disp[i])
accel_disp[i] = d;
}
+
/* still detector with hysteresis */
- if ( accel_disp[0] < still_thr2 &&
- accel_disp[1] < still_thr2 &&
- accel_disp[2] < still_thr2 ) {
+ if (accel_disp[0] < still_thr2 &&
+ accel_disp[1] < still_thr2 &&
+ accel_disp[2] < still_thr2) {
/* is still now */
if (t_still == 0) {
/* first time */
mavlink_log_info(mavlink_fd, "detected rest position, waiting...");
t_still = t;
t_timeout = t + timeout;
+
} else {
/* still since t_still */
if (t > t_still + still_time) {
@@ -349,62 +407,71 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
break;
}
}
- } else if ( accel_disp[0] > still_thr2 * 2.0f ||
- accel_disp[1] > still_thr2 * 2.0f ||
- accel_disp[2] > still_thr2 * 2.0f) {
+
+ } else if (accel_disp[0] > still_thr2 * 4.0f ||
+ accel_disp[1] > still_thr2 * 4.0f ||
+ accel_disp[2] > still_thr2 * 4.0f) {
/* not still, reset still start time */
if (t_still != 0) {
- mavlink_log_info(mavlink_fd, "detected motion, please hold still...");
+ mavlink_log_info(mavlink_fd, "detected motion, hold still...");
t_still = 0;
}
}
+
} else if (poll_ret == 0) {
poll_errcount++;
}
+
if (t > t_timeout) {
poll_errcount++;
}
if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: Failed reading sensor");
- return -1;
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ return ERROR;
}
}
- if ( fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr )
+ if (fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
return 0; // [ g, 0, 0 ]
- if ( fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr )
+
+ if (fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
return 1; // [ -g, 0, 0 ]
- if ( fabsf(accel_ema[0]) < accel_err_thr &&
- fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr )
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
return 2; // [ 0, g, 0 ]
- if ( fabsf(accel_ema[0]) < accel_err_thr &&
- fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr )
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
+ fabsf(accel_ema[2]) < accel_err_thr)
return 3; // [ 0, -g, 0 ]
- if ( fabsf(accel_ema[0]) < accel_err_thr &&
- fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr )
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr)
return 4; // [ 0, 0, g ]
- if ( fabsf(accel_ema[0]) < accel_err_thr &&
- fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr )
+
+ if (fabsf(accel_ema[0]) < accel_err_thr &&
+ fabsf(accel_ema[1]) < accel_err_thr &&
+ fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr)
return 5; // [ 0, 0, -g ]
- mavlink_log_info(mavlink_fd, "ERROR: invalid orientation");
+ mavlink_log_critical(mavlink_fd, "ERROR: invalid orientation");
- return -2; // Can't detect orientation
+ return ERROR; // Can't detect orientation
}
/*
* Read specified number of accelerometer samples, calculate average and dispersion.
*/
-int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num) {
+int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num)
+{
struct pollfd fds[1];
fds[0].fd = sensor_combined_sub;
fds[0].events = POLLIN;
@@ -415,12 +482,16 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
while (count < samples_num) {
int poll_ret = poll(fds, 1, 1000);
+
if (poll_ret == 1) {
struct sensor_combined_s sensor;
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+
for (int i = 0; i < 3; i++)
accel_sum[i] += sensor.accelerometer_m_s2[i];
+
count++;
+
} else {
errcount++;
continue;
@@ -437,10 +508,12 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
return OK;
}
-int mat_invert3(float src[3][3], float dst[3][3]) {
+int mat_invert3(float src[3][3], float dst[3][3])
+{
float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) -
- src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
- src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
+ src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
+ src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
+
if (det == 0.0f)
return ERROR; // Singular matrix
@@ -457,7 +530,8 @@ int mat_invert3(float src[3][3], float dst[3][3]) {
return OK;
}
-int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g) {
+int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g)
+{
/* calculate offsets */
for (int i = 0; i < 3; i++) {
accel_offs[i] = (accel_ref[i * 2][i] + accel_ref[i * 2 + 1][i]) / 2;
@@ -466,6 +540,7 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
/* fill matrix A for linear equations system*/
float mat_A[3][3];
memset(mat_A, 0, sizeof(mat_A));
+
for (int i = 0; i < 3; i++) {
for (int j = 0; j < 3; j++) {
float a = accel_ref[i * 2][j] - accel_offs[j];
@@ -475,6 +550,7 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
/* calculate inverse matrix for A */
float mat_A_inv[3][3];
+
if (mat_invert3(mat_A, mat_A_inv) != OK)
return ERROR;
diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h
new file mode 100644
index 000000000..fd8b8564d
--- /dev/null
+++ b/src/modules/commander/calibration_messages.h
@@ -0,0 +1,57 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file calibration_messages.h
+ *
+ * Common calibration messages.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef CALIBRATION_MESSAGES_H_
+#define CALIBRATION_MESSAGES_H_
+
+#define CAL_STARTED_MSG "%s calibration: started"
+#define CAL_DONE_MSG "%s calibration: done"
+#define CAL_FAILED_MSG "%s calibration: failed"
+#define CAL_PROGRESS_MSG "%s calibration: progress <%u>"
+
+#define CAL_FAILED_SENSOR_MSG "ERROR: failed reading sensor"
+#define CAL_FAILED_RESET_CAL_MSG "ERROR: failed to reset calibration"
+#define CAL_FAILED_APPLY_CAL_MSG "ERROR: failed to apply calibration"
+#define CAL_FAILED_SET_PARAMS_MSG "ERROR: failed to set parameters"
+#define CAL_FAILED_SAVE_PARAMS_MSG "ERROR: failed to save parameters"
+
+#endif /* CALIBRATION_MESSAGES_H_ */
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 2ef509980..9814a7bcc 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -369,8 +369,10 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
if (hil_ret == OK && control_mode->flag_system_hil_enabled) {
/* reset the arming mode to disarmed */
arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_STANDBY, armed);
+
if (arming_res != TRANSITION_DENIED) {
mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
+
} else {
mavlink_log_info(mavlink_fd, "[cmd] HIL: FAILED resetting armed state");
}
@@ -481,27 +483,28 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
break;
}
- case VEHICLE_CMD_COMPONENT_ARM_DISARM:
- {
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
- if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
- if (safety->safety_switch_available && !safety->safety_off) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
- arming_res = TRANSITION_DENIED;
+ case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
- } else {
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
- }
+ if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
+ if (safety->safety_switch_available && !safety->safety_off) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+ arming_res = TRANSITION_DENIED;
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by component arm cmd");
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- } else {
- mavlink_log_info(mavlink_fd, "[cmd] REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ } else {
+ arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
+ }
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by component arm cmd");
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ mavlink_log_info(mavlink_fd, "[cmd] REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
}
}
- }
break;
default:
@@ -687,7 +690,7 @@ int commander_thread_main(int argc, char *argv[])
bool updated = false;
- bool rc_calibration_ok = (OK == rc_calibration_check());
+ bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
/* Subscribe to safety topic */
int safety_sub = orb_subscribe(ORB_ID(safety));
@@ -802,7 +805,7 @@ int commander_thread_main(int argc, char *argv[])
status_changed = true;
/* re-check RC calibration */
- rc_calibration_ok = (OK == rc_calibration_check());
+ rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
/* navigation parameters */
param_get(_param_takeoff_alt, &takeoff_alt);
@@ -940,7 +943,7 @@ int commander_thread_main(int argc, char *argv[])
last_idle_time = system_load.tasks[0].total_runtime;
/* check if board is connected via USB */
- struct stat statbuf;
+ //struct stat statbuf;
//on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0);
}
@@ -970,6 +973,7 @@ int commander_thread_main(int argc, char *argv[])
if (armed.armed) {
arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED_ERROR, &armed);
+
} else {
arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY_ERROR, &armed);
}
@@ -1244,12 +1248,14 @@ int commander_thread_main(int argc, char *argv[])
counter++;
int blink_state = blink_msg_state();
+
if (blink_state > 0) {
/* blinking LED message, don't touch LEDs */
if (blink_state == 2) {
/* blinking LED message completed, restore normal state */
control_status_leds(&status, &armed, true);
}
+
} else {
/* normal state */
control_status_leds(&status, &armed, status_changed);
@@ -1264,7 +1270,7 @@ int commander_thread_main(int argc, char *argv[])
ret = pthread_join(commander_low_prio_thread, NULL);
if (ret) {
- warn("join failed", ret);
+ warn("join failed: %d", ret);
}
rgbled_set_mode(RGBLED_MODE_OFF);
@@ -1308,6 +1314,7 @@ control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool chan
/* driving rgbled */
if (changed) {
bool set_normal_color = false;
+
/* set mode */
if (status->arming_state == ARMING_STATE_ARMED) {
rgbled_set_mode(RGBLED_MODE_ON);
@@ -1332,6 +1339,7 @@ control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool chan
if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
rgbled_set_color(RGBLED_COLOR_AMBER);
}
+
/* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */
} else {
@@ -1694,11 +1702,10 @@ void *commander_low_prio_loop(void *arg)
fds[0].events = POLLIN;
while (!thread_should_exit) {
-
- /* wait for up to 100ms for data */
+ /* wait for up to 200ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 200);
- /* timed out - periodic check for _task_should_exit, etc. */
+ /* timed out - periodic check for thread_should_exit, etc. */
if (pret == 0)
continue;
@@ -1773,7 +1780,7 @@ void *commander_low_prio_loop(void *arg)
} else if ((int)(cmd.param4) == 1) {
/* RC calibration */
- answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_rc_calibration(mavlink_fd);
} else if ((int)(cmd.param5) == 1) {
@@ -1854,7 +1861,6 @@ void *commander_low_prio_loop(void *arg)
/* send acknowledge command */
// XXX TODO
}
-
}
close(cmd_sub);
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 369e6da62..30cd0d48d 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -33,10 +33,12 @@
/**
* @file gyro_calibration.cpp
+ *
* Gyroscope calibration routine
*/
#include "gyro_calibration.h"
+#include "calibration_messages.h"
#include "commander_helper.h"
#include <stdio.h>
@@ -56,21 +58,14 @@
#endif
static const int ERROR = -1;
+static const char *sensor_name = "gyro";
+
int do_gyro_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "Gyro calibration starting, do not move unit.");
-
- const unsigned calibration_count = 5000;
-
- int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s raw;
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
- unsigned calibration_counter = 0;
- float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
-
- /* set offsets to zero */
- int fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale_null = {
+ struct gyro_scale gyro_scale = {
0.0f,
1.0f,
0.0f,
@@ -79,97 +74,100 @@ int do_gyro_calibration(int mavlink_fd)
1.0f,
};
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
- warn("WARNING: failed to set scale / offsets for gyro");
+ int res = OK;
+ /* reset all offsets to zero and all scales to one */
+ int fd = open(GYRO_DEVICE_PATH, 0);
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
close(fd);
- unsigned poll_errcount = 0;
-
- while (calibration_counter < calibration_count) {
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
- /* wait blocking for new data */
- struct pollfd fds[1];
- fds[0].fd = sub_sensor_combined;
- fds[0].events = POLLIN;
+ if (res == OK) {
+ /* determine gyro mean values */
+ const unsigned calibration_count = 5000;
+ unsigned calibration_counter = 0;
+ unsigned poll_errcount = 0;
+
+ /* subscribe to gyro sensor topic */
+ int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
+ struct gyro_report gyro_report;
+
+ while (calibration_counter < calibration_count) {
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_gyro;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_gyro), sub_sensor_gyro, &gyro_report);
+ gyro_scale.x_offset += gyro_report.x;
+ gyro_scale.y_offset += gyro_report.y;
+ gyro_scale.z_offset += gyro_report.z;
+ calibration_counter++;
+
+ if (calibration_counter % (calibration_count / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
+ }
- int poll_ret = poll(fds, 1, 1000);
+ close(sub_sensor_gyro);
- if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- gyro_offset[0] += raw.gyro_rad_s[0];
- gyro_offset[1] += raw.gyro_rad_s[1];
- gyro_offset[2] += raw.gyro_rad_s[2];
- calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
- mavlink_log_info(mavlink_fd, "gyro cal progress <%u> percent", (calibration_counter * 100) / calibration_count);
-
- } else {
- poll_errcount++;
- }
+ gyro_scale.x_offset /= calibration_count;
+ gyro_scale.y_offset /= calibration_count;
+ gyro_scale.z_offset /= calibration_count;
+ }
- if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: Failed reading gyro sensor");
- close(sub_sensor_combined);
- return ERROR;
+ if (res == OK) {
+ /* check offsets */
+ if (!isfinite(gyro_scale.x_offset) || !isfinite(gyro_scale.y_offset) || !isfinite(gyro_scale.z_offset)) {
+ mavlink_log_critical(mavlink_fd, "ERROR: offset is NaN");
+ res = ERROR;
}
}
- gyro_offset[0] = gyro_offset[0] / calibration_count;
- gyro_offset[1] = gyro_offset[1] / calibration_count;
- gyro_offset[2] = gyro_offset[2] / calibration_count;
-
-
- if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
-
- if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
- || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
- || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
+ if (res == OK) {
+ /* set offset parameters to new values */
+ if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_scale.x_offset))
+ || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_scale.y_offset))
+ || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_scale.z_offset))) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set offset params");
+ res = ERROR;
}
+ }
- /* set offsets to actual value */
- fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- 1.0f,
- gyro_offset[1],
- 1.0f,
- gyro_offset[2],
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
+#if 0
+ /* beep on offset calibration end */
+ mavlink_log_info(mavlink_fd, "gyro offset calibration done");
+ tune_neutral();
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
+ /* scale calibration */
+ /* this was only a proof of concept and is currently not working. scaling will be set to 1.0 for now. */
- if (save_ret != 0) {
- warnx("WARNING: auto-save of params to storage failed");
- mavlink_log_critical(mavlink_fd, "gyro store failed");
- close(sub_sensor_combined);
- return ERROR;
- }
+ mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
+ warnx("offset calibration finished. Rotate for scale 30x, or do not rotate and wait for 5 seconds to skip.");
- tune_neutral();
- /* third beep by cal end routine */
+ /* apply new offsets */
+ fd = open(GYRO_DEVICE_PATH, 0);
- } else {
- mavlink_log_info(mavlink_fd, "offset cal FAILED (NaN)");
- close(sub_sensor_combined);
- return ERROR;
- }
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ warn("WARNING: failed to apply new offsets for gyro");
- mavlink_log_info(mavlink_fd, "offset calibration done.");
+ close(fd);
-#if 0
- /*** --- SCALING --- ***/
-
- mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
- warnx("offset calibration finished. Rotate for scale 30x, or do not rotate and wait for 5 seconds to skip.");
unsigned rotations_count = 30;
float gyro_integral = 0.0f;
@@ -178,9 +176,11 @@ int do_gyro_calibration(int mavlink_fd)
// XXX change to mag topic
orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- float mag_last = -atan2f(raw.magnetometer_ga[1],raw.magnetometer_ga[0]);
- if (mag_last > M_PI_F) mag_last -= 2*M_PI_F;
- if (mag_last < -M_PI_F) mag_last += 2*M_PI_F;
+ float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
+
+ if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+
+ if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
uint64_t last_time = hrt_absolute_time();
@@ -190,7 +190,7 @@ int do_gyro_calibration(int mavlink_fd)
/* abort this loop if not rotated more than 180 degrees within 5 seconds */
if ((fabsf(baseline_integral / (2.0f * M_PI_F)) < 0.6f)
- && (hrt_absolute_time() - start_time > 5 * 1e6)) {
+ && (hrt_absolute_time() - start_time > 5 * 1e6)) {
mavlink_log_info(mavlink_fd, "scale skipped, gyro calibration done");
close(sub_sensor_combined);
return OK;
@@ -218,14 +218,17 @@ int do_gyro_calibration(int mavlink_fd)
// calculate error between estimate and measurement
// apply declination correction for true heading as well.
//float mag = -atan2f(magNav(1),magNav(0));
- float mag = -atan2f(raw.magnetometer_ga[1],raw.magnetometer_ga[0]);
- if (mag > M_PI_F) mag -= 2*M_PI_F;
- if (mag < -M_PI_F) mag += 2*M_PI_F;
+ float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
+
+ if (mag > M_PI_F) mag -= 2 * M_PI_F;
+
+ if (mag < -M_PI_F) mag += 2 * M_PI_F;
float diff = mag - mag_last;
- if (diff > M_PI_F) diff -= 2*M_PI_F;
- if (diff < -M_PI_F) diff += 2*M_PI_F;
+ if (diff > M_PI_F) diff -= 2 * M_PI_F;
+
+ if (diff < -M_PI_F) diff += 2 * M_PI_F;
baseline_integral += diff;
mag_last = mag;
@@ -235,63 +238,68 @@ int do_gyro_calibration(int mavlink_fd)
// warnx("dbg: b: %6.4f, g: %6.4f", (double)baseline_integral, (double)gyro_integral);
- // } else if (poll_ret == 0) {
- // /* any poll failure for 1s is a reason to abort */
- // mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
- // return;
+ // } else if (poll_ret == 0) {
+ // /* any poll failure for 1s is a reason to abort */
+ // mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
+ // return;
}
}
float gyro_scale = baseline_integral / gyro_integral;
-
+
warnx("gyro scale: yaw (z): %6.4f", (double)gyro_scale);
mavlink_log_info(mavlink_fd, "gyro scale: yaw (z): %6.4f", (double)gyro_scale);
-#else
- float gyro_scales[] = { 1.0f, 1.0f, 1.0f };
-#endif
-
+ if (!isfinite(gyro_scale.x_scale) || !isfinite(gyro_scale.y_scale) || !isfinite(gyro_scale.z_scale)) {
+ mavlink_log_info(mavlink_fd, "gyro scale calibration FAILED (NaN)");
+ close(sub_sensor_gyro);
+ mavlink_log_critical(mavlink_fd, "gyro calibration failed");
+ return ERROR;
+ }
- if (isfinite(gyro_scales[0]) && isfinite(gyro_scales[1]) && isfinite(gyro_scales[2])) {
+ /* beep on calibration end */
+ mavlink_log_info(mavlink_fd, "gyro scale calibration done");
+ tune_neutral();
- if (param_set(param_find("SENS_GYRO_XSCALE"), &(gyro_scales[0]))
- || param_set(param_find("SENS_GYRO_YSCALE"), &(gyro_scales[1]))
- || param_set(param_find("SENS_GYRO_ZSCALE"), &(gyro_scales[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro scale failed!");
+#endif
+
+ if (res == OK) {
+ /* set scale parameters to new values */
+ if (param_set(param_find("SENS_GYRO_XSCALE"), &(gyro_scale.x_scale))
+ || param_set(param_find("SENS_GYRO_YSCALE"), &(gyro_scale.y_scale))
+ || param_set(param_find("SENS_GYRO_ZSCALE"), &(gyro_scale.z_scale))) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set scale params");
+ res = ERROR;
}
+ }
- /* set offsets to actual value */
+ if (res == OK) {
+ /* apply new scaling and offsets */
fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- gyro_scales[0],
- gyro_offset[1],
- gyro_scales[1],
- gyro_offset[2],
- gyro_scales[2],
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
+ }
+
+ if (res == OK) {
/* auto-save to EEPROM */
- int save_ret = param_save_default();
+ res = param_save_default();
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
}
+ }
- mavlink_log_info(mavlink_fd, "gyro calibration done");
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- /* third beep by cal end routine */
- close(sub_sensor_combined);
- return OK;
} else {
- mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
- close(sub_sensor_combined);
- return ERROR;
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
+
+ return res;
}
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index b0d4266be..09f4104f8 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -33,12 +33,14 @@
/**
* @file mag_calibration.cpp
+ *
* Magnetometer calibration routine
*/
#include "mag_calibration.h"
#include "commander_helper.h"
#include "calibration_routines.h"
+#include "calibration_messages.h"
#include <stdio.h>
#include <stdlib.h>
@@ -59,26 +61,20 @@
#endif
static const int ERROR = -1;
+static const char *sensor_name = "mag";
+
int do_mag_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "please put the system in a rest position and wait.");
-
- int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
- struct mag_report mag;
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
/* 45 seconds */
uint64_t calibration_interval = 45 * 1000 * 1000;
- /* maximum 2000 values */
+ /* maximum 500 values */
const unsigned int calibration_maxcount = 500;
unsigned int calibration_counter = 0;
- /* limit update rate to get equally spaced measurements over time (in ms) */
- orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
-
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
-
- /* erase old calibration */
struct mag_scale mscale_null = {
0.0f,
1.0f,
@@ -88,97 +84,92 @@ int do_mag_calibration(int mavlink_fd)
1.0f,
};
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set scale / offsets for mag");
- mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
- }
+ int res = OK;
- /* calibrate range */
- if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
- warnx("failed to calibrate scale");
- }
+ /* erase old calibration */
+ int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null);
- close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
- mavlink_log_info(mavlink_fd, "mag cal progress <20> percent");
+ if (res == OK) {
+ /* calibrate range */
+ res = ioctl(fd, MAGIOCCALIBRATE, fd);
- /* calibrate offsets */
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to calibrate scale");
+ }
+ }
- // uint64_t calibration_start = hrt_absolute_time();
+ close(fd);
- uint64_t axis_deadline = hrt_absolute_time();
- uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+ float *x;
+ float *y;
+ float *z;
- const char axislabels[3] = { 'X', 'Y', 'Z'};
- int axis_index = -1;
+ if (res == OK) {
+ /* allocate memory */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
- float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
+ x = (float *)malloc(sizeof(float) * calibration_maxcount);
+ y = (float *)malloc(sizeof(float) * calibration_maxcount);
+ z = (float *)malloc(sizeof(float) * calibration_maxcount);
- if (x == NULL || y == NULL || z == NULL) {
- warnx("mag cal failed: out of memory");
- mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
- warnx("x:%p y:%p z:%p\n", x, y, z);
- return ERROR;
+ if (x == NULL || y == NULL || z == NULL) {
+ mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+ res = ERROR;
+ }
}
- mavlink_log_info(mavlink_fd, "scale calibration completed, dynamic calibration starting..");
+ if (res == OK) {
+ int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
+ struct mag_report mag;
- unsigned poll_errcount = 0;
+ /* limit update rate to get equally spaced measurements over time (in ms) */
+ orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
- while (hrt_absolute_time() < calibration_deadline &&
- calibration_counter < calibration_maxcount) {
+ /* calibrate offsets */
+ uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+ unsigned poll_errcount = 0;
- /* wait blocking for new data */
- struct pollfd fds[1];
- fds[0].fd = sub_mag;
- fds[0].events = POLLIN;
+ mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
- /* user guidance */
- if (hrt_absolute_time() >= axis_deadline &&
- axis_index < 3) {
+ while (hrt_absolute_time() < calibration_deadline &&
+ calibration_counter < calibration_maxcount) {
- axis_index++;
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_mag;
+ fds[0].events = POLLIN;
- mavlink_log_info(mavlink_fd, "please rotate in a figure 8 or around %c axis.", axislabels[axis_index]);
- tune_neutral();
+ int poll_ret = poll(fds, 1, 1000);
- axis_deadline += calibration_interval / 3;
- }
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
- if (!(axis_index < 3)) {
- break;
- }
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
+ x[calibration_counter] = mag.x;
+ y[calibration_counter] = mag.y;
+ z[calibration_counter] = mag.z;
- x[calibration_counter] = mag.x;
- y[calibration_counter] = mag.y;
- z[calibration_counter] = mag.z;
+ calibration_counter++;
- calibration_counter++;
- if (calibration_counter % (calibration_maxcount / 20) == 0)
- mavlink_log_info(mavlink_fd, "mag cal progress <%u> percent", 20 + (calibration_counter * 50) / calibration_maxcount);
+ if (calibration_counter % (calibration_maxcount / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ } else {
+ poll_errcount++;
+ }
- } else {
- poll_errcount++;
- }
-
- if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: Failed reading mag sensor");
- close(sub_mag);
- free(x);
- free(y);
- free(z);
- return ERROR;
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
}
-
+ close(sub_mag);
}
float sphere_x;
@@ -186,93 +177,100 @@ int do_mag_calibration(int mavlink_fd)
float sphere_z;
float sphere_radius;
- mavlink_log_info(mavlink_fd, "mag cal progress <70> percent");
- sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
- mavlink_log_info(mavlink_fd, "mag cal progress <80> percent");
+ if (res == OK) {
+ /* sphere fit */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
+ sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 80);
- free(x);
- free(y);
- free(z);
+ if (!isfinite(sphere_x) || !isfinite(sphere_y) || !isfinite(sphere_z)) {
+ mavlink_log_critical(mavlink_fd, "ERROR: NaN in sphere fit");
+ res = ERROR;
+ }
+ }
- if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
+ if (x != NULL)
+ free(x);
- fd = open(MAG_DEVICE_PATH, 0);
+ if (y != NULL)
+ free(y);
- struct mag_scale mscale;
+ if (z != NULL)
+ free(z);
- if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to get scale / offsets for mag");
+ if (res == OK) {
+ /* apply calibration and set parameters */
+ struct mag_scale mscale;
- mscale.x_offset = sphere_x;
- mscale.y_offset = sphere_y;
- mscale.z_offset = sphere_z;
+ fd = open(MAG_DEVICE_PATH, 0);
+ res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale);
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to set scale / offsets for mag");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to get current calibration");
+ }
- close(fd);
+ if (res == OK) {
+ mscale.x_offset = sphere_x;
+ mscale.y_offset = sphere_y;
+ mscale.z_offset = sphere_z;
- /* announce and set new offset */
+ res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale);
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
- warnx("Setting X mag offset failed!\n");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
}
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
- warnx("Setting Y mag offset failed!\n");
- }
+ close(fd);
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
- warnx("Setting Z mag offset failed!\n");
- }
+ if (res == OK) {
+ /* set parameters */
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ res = ERROR;
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
- warnx("Setting X mag scale failed!\n");
- }
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ res = ERROR;
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
- warnx("Setting Y mag scale failed!\n");
- }
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ res = ERROR;
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
- warnx("Setting Z mag scale failed!\n");
- }
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ res = ERROR;
- mavlink_log_info(mavlink_fd, "mag cal progress <90> percent");
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ res = ERROR;
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ }
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- mavlink_log_info(mavlink_fd, "FAILED storing calibration");
- close(sub_mag);
- return ERROR;
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 90);
}
- warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
- (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
- (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
+ if (res == OK) {
+ /* auto-save to EEPROM */
+ res = param_save_default();
- char buf[52];
- sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
- (double)mscale.y_offset, (double)mscale.z_offset);
- mavlink_log_info(mavlink_fd, buf);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
+ }
+ }
- sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
- (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
+ (double)mscale.y_offset, (double)mscale.z_offset);
+ mavlink_log_info(mavlink_fd, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
+ (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, "magnetometer calibration completed");
- mavlink_log_info(mavlink_fd, "mag cal progress <100> percent");
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- close(sub_mag);
- return OK;
- /* third beep by cal end routine */
+ } else {
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ }
- } else {
- mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
- close(sub_mag);
- return ERROR;
+ return res;
}
}
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 91d75121e..554dfcb08 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -47,4 +47,3 @@ SRCS = commander.cpp \
baro_calibration.cpp \
rc_calibration.cpp \
airspeed_calibration.cpp
-
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index edb21c7ab..61a54170a 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -610,6 +610,15 @@ int sdlog2_thread_main(int argc, char *argv[])
errx(1, "unable to create logging folder, exiting.");
}
+ const char *converter_in = "/etc/logging/conv.zip";
+ char* converter_out = malloc(120);
+ sprintf(converter_out, "%s/conv.zip", folder_path);
+
+ if (file_copy(converter_in, converter_out)) {
+ errx(1, "unable to copy conversion scripts, exiting.");
+ }
+ free(converter_out);
+
/* only print logging path, important to find log file later */
warnx("logging to directory: %s", folder_path);
@@ -1278,7 +1287,7 @@ int file_copy(const char *file_old, const char *file_new)
fclose(source);
fclose(target);
- return ret;
+ return OK;
}
void handle_command(struct vehicle_command_s *cmd)
diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp
index b1dc39445..96a443c6e 100644
--- a/src/modules/segway/BlockSegwayController.cpp
+++ b/src/modules/segway/BlockSegwayController.cpp
@@ -26,7 +26,7 @@ void BlockSegwayController::update() {
_actuators.control[i] = 0.0f;
// only update guidance in auto mode
- if (_status.state_machine == SYSTEM_STATE_AUTO) {
+ if (_status.main_state == MAIN_STATE_AUTO) {
// update guidance
}
@@ -34,17 +34,18 @@ void BlockSegwayController::update() {
float spdCmd = -th2v.update(_att.pitch) - q2v.update(_att.pitchspeed);
// handle autopilot modes
- if (_status.state_machine == SYSTEM_STATE_AUTO ||
- _status.state_machine == SYSTEM_STATE_STABILIZED) {
+ if (_status.main_state == MAIN_STATE_AUTO ||
+ _status.main_state == MAIN_STATE_SEATBELT ||
+ _status.main_state == MAIN_STATE_EASY) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
- } else if (_status.state_machine == SYSTEM_STATE_MANUAL) {
- if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+ } else if (_status.main_state == MAIN_STATE_MANUAL) {
+ if (_status.navigation_state == NAVIGATION_STATE_DIRECT) {
_actuators.control[CH_LEFT] = _manual.throttle;
_actuators.control[CH_RIGHT] = _manual.pitch;
- } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
+ } else if (_status.navigation_state == NAVIGATION_STATE_STABILIZE) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
}
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 4d719e0e1..8875f65fc 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -44,8 +44,34 @@
#include <systemlib/param/param.h>
+/**
+ * Gyro X offset FIXME
+ *
+ * This is an X-axis offset for the gyro.
+ * Adjust it according to the calibration data.
+ *
+ * @min -10.0
+ * @max 10.0
+ * @group Gyro Config
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
+
+/**
+ * Gyro Y offset FIXME with dot.
+ *
+ * @min -10.0
+ * @max 10.0
+ * @group Gyro Config
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
+
+/**
+ * Gyro Z offset FIXME
+ *
+ * @min -5.0
+ * @max 5.0
+ * @group Gyro Config
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 3fcacaf8f..1b79de8fd 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -67,6 +67,7 @@
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
+#include <conversion/rotation.h>
#include <systemlib/airspeed.h>
@@ -136,75 +137,6 @@
#define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg)
/**
- * Enum for board and external compass rotations.
- * This enum maps from board attitude to airframe attitude.
- */
-enum Rotation {
- ROTATION_NONE = 0,
- ROTATION_YAW_45 = 1,
- ROTATION_YAW_90 = 2,
- ROTATION_YAW_135 = 3,
- ROTATION_YAW_180 = 4,
- ROTATION_YAW_225 = 5,
- ROTATION_YAW_270 = 6,
- ROTATION_YAW_315 = 7,
- ROTATION_ROLL_180 = 8,
- ROTATION_ROLL_180_YAW_45 = 9,
- ROTATION_ROLL_180_YAW_90 = 10,
- ROTATION_ROLL_180_YAW_135 = 11,
- ROTATION_PITCH_180 = 12,
- ROTATION_ROLL_180_YAW_225 = 13,
- ROTATION_ROLL_180_YAW_270 = 14,
- ROTATION_ROLL_180_YAW_315 = 15,
- ROTATION_ROLL_90 = 16,
- ROTATION_ROLL_90_YAW_45 = 17,
- ROTATION_ROLL_90_YAW_90 = 18,
- ROTATION_ROLL_90_YAW_135 = 19,
- ROTATION_ROLL_270 = 20,
- ROTATION_ROLL_270_YAW_45 = 21,
- ROTATION_ROLL_270_YAW_90 = 22,
- ROTATION_ROLL_270_YAW_135 = 23,
- ROTATION_PITCH_90 = 24,
- ROTATION_PITCH_270 = 25,
- ROTATION_MAX
-};
-
-typedef struct {
- uint16_t roll;
- uint16_t pitch;
- uint16_t yaw;
-} rot_lookup_t;
-
-const rot_lookup_t rot_lookup[] = {
- { 0, 0, 0 },
- { 0, 0, 45 },
- { 0, 0, 90 },
- { 0, 0, 135 },
- { 0, 0, 180 },
- { 0, 0, 225 },
- { 0, 0, 270 },
- { 0, 0, 315 },
- {180, 0, 0 },
- {180, 0, 45 },
- {180, 0, 90 },
- {180, 0, 135 },
- { 0, 180, 0 },
- {180, 0, 225 },
- {180, 0, 270 },
- {180, 0, 315 },
- { 90, 0, 0 },
- { 90, 0, 45 },
- { 90, 0, 90 },
- { 90, 0, 135 },
- {270, 0, 0 },
- {270, 0, 45 },
- {270, 0, 90 },
- {270, 0, 135 },
- { 0, 90, 0 },
- { 0, 270, 0 }
-};
-
-/**
* Sensor app start / stop handling function
*
* @ingroup apps
@@ -385,11 +317,6 @@ private:
int parameters_update();
/**
- * Get the rotation matrices
- */
- void get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix);
-
- /**
* Do accel-related initialisation.
*/
void accel_init();
@@ -804,24 +731,6 @@ Sensors::parameters_update()
}
void
-Sensors::get_rot_matrix(enum Rotation rot, math::Matrix *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);
-}
-
-void
Sensors::accel_init()
{
int fd;
diff --git a/src/modules/systemlib/mixer/mixer.cpp b/src/modules/systemlib/mixer/mixer.cpp
index b1bb1a66d..cce46bf5f 100644
--- a/src/modules/systemlib/mixer/mixer.cpp
+++ b/src/modules/systemlib/mixer/mixer.cpp
@@ -50,6 +50,8 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <ctype.h>
+#include <systemlib/err.h>
#include "mixer.h"
@@ -114,6 +116,33 @@ Mixer::scale_check(struct mixer_scaler_s &scaler)
return 0;
}
+const char *
+Mixer::findtag(const char *buf, unsigned &buflen, char tag)
+{
+ while (buflen >= 2) {
+ if ((buf[0] == tag) && (buf[1] == ':'))
+ return buf;
+ buf++;
+ buflen--;
+ }
+ return nullptr;
+}
+
+const char *
+Mixer::skipline(const char *buf, unsigned &buflen)
+{
+ const char *p;
+
+ /* if we can find a CR or NL in the buffer, skip up to it */
+ if ((p = (const char *)memchr(buf, '\r', buflen)) || (p = (const char *)memchr(buf, '\n', buflen))) {
+ /* skip up to it AND one beyond - could be on the NUL symbol now */
+ buflen -= (p - buf) + 1;
+ return p + 1;
+ }
+
+ return nullptr;
+}
+
/****************************************************************************/
NullMixer::NullMixer() :
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index bbfa130a9..723bf9f3b 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -128,7 +128,9 @@
#ifndef _SYSTEMLIB_MIXER_MIXER_H
#define _SYSTEMLIB_MIXER_MIXER_H value
+#include <nuttx/config.h>
#include "drivers/drv_mixer.h"
+#include "mixer_load.h"
/**
* Abstract class defining a mixer mixing zero or more inputs to
@@ -210,6 +212,24 @@ protected:
*/
static int scale_check(struct mixer_scaler_s &scaler);
+ /**
+ * Find a tag
+ *
+ * @param buf The buffer to operate on.
+ * @param buflen length of the buffer.
+ * @param tag character to search for.
+ */
+ static const char * findtag(const char *buf, unsigned &buflen, char tag);
+
+ /**
+ * Skip a line
+ *
+ * @param buf The buffer to operate on.
+ * @param buflen length of the buffer.
+ * @return 0 / OK if a line could be skipped, 1 else
+ */
+ static const char * skipline(const char *buf, unsigned &buflen);
+
private:
};
@@ -239,6 +259,11 @@ public:
void reset();
/**
+ * Count the mixers in the group.
+ */
+ unsigned count();
+
+ /**
* Adds mixers to the group based on a text description in a buffer.
*
* Mixer definitions begin with a single capital letter and a colon.
diff --git a/src/modules/systemlib/mixer/mixer_group.cpp b/src/modules/systemlib/mixer/mixer_group.cpp
index 1dbc512cd..3ed99fba0 100644
--- a/src/modules/systemlib/mixer/mixer_group.cpp
+++ b/src/modules/systemlib/mixer/mixer_group.cpp
@@ -111,6 +111,20 @@ MixerGroup::mix(float *outputs, unsigned space)
return index;
}
+unsigned
+MixerGroup::count()
+{
+ Mixer *mixer = _first;
+ unsigned index = 0;
+
+ while ((mixer != nullptr)) {
+ mixer = mixer->_next;
+ index++;
+ }
+
+ return index;
+}
+
void
MixerGroup::groups_required(uint32_t &groups)
{
@@ -170,6 +184,7 @@ MixerGroup::load_from_buf(const char *buf, unsigned &buflen)
/* only adjust buflen if parsing was successful */
buflen = resid;
+ debug("SUCCESS - buflen: %d", buflen);
} else {
/*
diff --git a/src/modules/systemlib/mixer/mixer_load.c b/src/modules/systemlib/mixer/mixer_load.c
new file mode 100644
index 000000000..a55ddf8a3
--- /dev/null
+++ b/src/modules/systemlib/mixer/mixer_load.c
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * 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 mixer_load.c
+ *
+ * Programmable multi-channel mixer library.
+ */
+
+#include <nuttx/config.h>
+#include <string.h>
+#include <stdio.h>
+#include <ctype.h>
+
+#include "mixer_load.h"
+
+int load_mixer_file(const char *fname, char *buf, unsigned maxlen)
+{
+ FILE *fp;
+ char line[120];
+
+ /* open the mixer definition file */
+ fp = fopen(fname, "r");
+ if (fp == NULL) {
+ return 1;
+ }
+
+ /* read valid lines from the file into a buffer */
+ buf[0] = '\0';
+ for (;;) {
+
+ /* get a line, bail on error/EOF */
+ line[0] = '\0';
+ if (fgets(line, sizeof(line), fp) == NULL)
+ break;
+
+ /* if the line doesn't look like a mixer definition line, skip it */
+ if ((strlen(line) < 2) || !isupper(line[0]) || (line[1] != ':'))
+ continue;
+
+ /* compact whitespace in the buffer */
+ char *t, *f;
+ for (f = line; *f != '\0'; f++) {
+ /* scan for space characters */
+ if (*f == ' ') {
+ /* look for additional spaces */
+ t = f + 1;
+ while (*t == ' ')
+ t++;
+ if (*t == '\0') {
+ /* strip trailing whitespace */
+ *f = '\0';
+ } else if (t > (f + 1)) {
+ memmove(f + 1, t, strlen(t) + 1);
+ }
+ }
+ }
+
+ /* if the line is too long to fit in the buffer, bail */
+ if ((strlen(line) + strlen(buf) + 1) >= maxlen) {
+ return 1;
+ }
+
+ /* add the line to the buffer */
+ strcat(buf, line);
+ }
+
+ return 0;
+}
+
diff --git a/src/modules/systemlib/mixer/mixer_load.h b/src/modules/systemlib/mixer/mixer_load.h
new file mode 100644
index 000000000..4b7091d5b
--- /dev/null
+++ b/src/modules/systemlib/mixer/mixer_load.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * 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 mixer_load.h
+ *
+ */
+
+
+#ifndef _SYSTEMLIB_MIXER_LOAD_H
+#define _SYSTEMLIB_MIXER_LOAD_H value
+
+#include <nuttx/config.h>
+
+__BEGIN_DECLS
+
+__EXPORT int load_mixer_file(const char *fname, char *buf, unsigned maxlen);
+
+__END_DECLS
+
+#endif
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 2446cc3fb..b89f341b6 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -130,7 +130,7 @@ const MultirotorMixer::Rotor _config_octa_plus[] = {
{ 1.000000, 0.000000, -1.00 },
{ -1.000000, 0.000000, -1.00 },
};
-const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
+const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_quad_x[0],
&_config_quad_plus[0],
&_config_quad_v[0],
@@ -140,7 +140,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOME
&_config_octa_x[0],
&_config_octa_plus[0],
};
-const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
+const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
4, /* quad_x */
4, /* quad_plus */
4, /* quad_v */
@@ -205,11 +205,17 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
}
if (used > (int)buflen) {
- debug("multirotor spec used %d of %u", used, buflen);
+ debug("OVERFLOW: multirotor spec used %d of %u", used, buflen);
return nullptr;
}
- buflen -= used;
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ return nullptr;
+ }
+
+ debug("remaining in buf: %d, first char: %c", buflen, buf[0]);
if (!strcmp(geomname, "4+")) {
geometry = MultirotorMixer::QUAD_PLUS;
diff --git a/src/modules/systemlib/mixer/mixer_simple.cpp b/src/modules/systemlib/mixer/mixer_simple.cpp
index c8434f991..c3985b5de 100644
--- a/src/modules/systemlib/mixer/mixer_simple.cpp
+++ b/src/modules/systemlib/mixer/mixer_simple.cpp
@@ -55,7 +55,7 @@
#include "mixer.h"
#define debug(fmt, args...) do { } while(0)
-// #define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
+//#define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
SimpleMixer::SimpleMixer(ControlCallback control_cb,
uintptr_t cb_handle,
@@ -71,28 +71,6 @@ SimpleMixer::~SimpleMixer()
free(_info);
}
-static const char *
-findtag(const char *buf, unsigned &buflen, char tag)
-{
- while (buflen >= 2) {
- if ((buf[0] == tag) && (buf[1] == ':'))
- return buf;
- buf++;
- buflen--;
- }
- return nullptr;
-}
-
-static void
-skipline(const char *buf, unsigned &buflen)
-{
- const char *p;
-
- /* if we can find a CR or NL in the buffer, skip up to it */
- if ((p = (const char *)memchr(buf, '\r', buflen)) || (p = (const char *)memchr(buf, '\n', buflen)))
- buflen -= (p - buf);
-}
-
int
SimpleMixer::parse_output_scaler(const char *buf, unsigned &buflen, mixer_scaler_s &scaler)
{
@@ -111,7 +89,12 @@ SimpleMixer::parse_output_scaler(const char *buf, unsigned &buflen, mixer_scaler
debug("out scaler parse failed on '%s' (got %d, consumed %d)", buf, ret, n);
return -1;
}
- skipline(buf, buflen);
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ return -1;
+ }
scaler.negative_scale = s[0] / 10000.0f;
scaler.positive_scale = s[1] / 10000.0f;
@@ -130,7 +113,7 @@ SimpleMixer::parse_control_scaler(const char *buf, unsigned &buflen, mixer_scale
buf = findtag(buf, buflen, 'S');
if ((buf == nullptr) || (buflen < 16)) {
- debug("contorl parser failed finding tag, ret: '%s'", buf);
+ debug("control parser failed finding tag, ret: '%s'", buf);
return -1;
}
@@ -139,7 +122,12 @@ SimpleMixer::parse_control_scaler(const char *buf, unsigned &buflen, mixer_scale
debug("control parse failed on '%s'", buf);
return -1;
}
- skipline(buf, buflen);
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ return -1;
+ }
control_group = u[0];
control_index = u[1];
@@ -161,29 +149,17 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
int used;
const char *end = buf + buflen;
- /* enforce that the mixer ends with space or a new line */
- for (int i = buflen - 1; i >= 0; i--) {
- if (buf[i] == '\0')
- continue;
-
- /* require a space or newline at the end of the buffer, fail on printable chars */
- if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
- /* found a line ending or space, so no split symbols / numbers. good. */
- break;
- } else {
- debug("simple parser rejected: No newline / space at end of buf. (#%d/%d: 0x%02x)", i, buflen-1, buf[i]);
- goto out;
- }
-
- }
-
/* get the base info for the mixer */
if (sscanf(buf, "M: %u%n", &inputs, &used) != 1) {
debug("simple parse failed on '%s'", buf);
goto out;
}
- buflen -= used;
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ goto out;
+ }
mixinfo = (mixer_simple_s *)malloc(MIXER_SIMPLE_SIZE(inputs));
diff --git a/src/modules/systemlib/mixer/module.mk b/src/modules/systemlib/mixer/module.mk
index 4d45e1c50..fc7485e20 100644
--- a/src/modules/systemlib/mixer/module.mk
+++ b/src/modules/systemlib/mixer/module.mk
@@ -39,4 +39,5 @@ LIBNAME = mixerlib
SRCS = mixer.cpp \
mixer_group.cpp \
mixer_multirotor.cpp \
- mixer_simple.cpp
+ mixer_simple.cpp \
+ mixer_load.c
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index ccdb2ea38..398657dd7 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -508,64 +508,63 @@ param_get_default_file(void)
int
param_save_default(void)
{
- int result;
- unsigned retries = 0;
-
- /* delete the file in case it exists */
- struct stat buffer;
- if (stat(param_get_default_file(), &buffer) == 0) {
-
- do {
- result = unlink(param_get_default_file());
- if (result != 0) {
- retries++;
- usleep(1000 * retries);
- }
- } while (result != OK && retries < 10);
+ int res;
+ int fd;
- if (result != OK)
- warnx("unlinking file %s failed.", param_get_default_file());
- }
+ const char *filename = param_get_default_file();
+ const char *filename_tmp = malloc(strlen(filename) + 5);
+ sprintf(filename_tmp, "%s.tmp", filename);
- /* create the file */
- int fd;
+ /* delete temp file if exist */
+ res = unlink(filename_tmp);
+
+ if (res != OK && errno == ENOENT)
+ res = OK;
+
+ if (res != OK)
+ warn("failed to delete temp file: %s", filename_tmp);
+
+ if (res == OK) {
+ /* write parameters to temp file */
+ fd = open(filename_tmp, O_WRONLY | O_CREAT | O_EXCL);
- do {
- /* do another attempt in case the unlink call is not synced yet */
- fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL);
if (fd < 0) {
- retries++;
- usleep(1000 * retries);
+ warn("failed to open temp file: %s", filename_tmp);
+ res = ERROR;
}
- } while (fd < 0 && retries < 10);
+ if (res == OK) {
+ res = param_export(fd, false);
- if (fd < 0) {
-
- warn("opening '%s' for writing failed", param_get_default_file());
- return fd;
- }
+ if (res != OK)
+ warnx("failed to write parameters to file: %s", filename_tmp);
+ }
- do {
- result = param_export(fd, false);
+ close(fd);
+ }
- if (result != OK) {
- retries++;
- usleep(1000 * retries);
- }
+ if (res == OK) {
+ /* delete parameters file */
+ res = unlink(filename);
- } while (result != 0 && retries < 10);
+ if (res != OK && errno == ENOENT)
+ res = OK;
+ if (res != OK)
+ warn("failed to delete parameters file: %s", filename);
+ }
- close(fd);
+ if (res == OK) {
+ /* rename temp file to parameters */
+ res = rename(filename_tmp, filename);
- if (result != OK) {
- warn("error exporting parameters to '%s'", param_get_default_file());
- (void)unlink(param_get_default_file());
- return result;
+ if (res != OK)
+ warn("failed to rename %s to %s", filename_tmp, filename);
}
- return 0;
+ free(filename_tmp);
+
+ return res;
}
/**
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
index 60d6473b8..b4350cc24 100644
--- a/src/modules/systemlib/rc_check.c
+++ b/src/modules/systemlib/rc_check.c
@@ -47,14 +47,12 @@
#include <mavlink/mavlink_log.h>
#include <uORB/topics/rc_channels.h>
-int rc_calibration_check(void) {
+int rc_calibration_check(int mavlink_fd) {
char nbuf[20];
param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
_parameter_handles_rev, _parameter_handles_dz;
- int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
float param_min, param_max, param_trim, param_rev, param_dz;
/* first check channel mappings */
diff --git a/src/modules/systemlib/rc_check.h b/src/modules/systemlib/rc_check.h
index e2238d151..e70b83cce 100644
--- a/src/modules/systemlib/rc_check.h
+++ b/src/modules/systemlib/rc_check.h
@@ -47,6 +47,6 @@
* @return 0 / OK if RC calibration is ok, index + 1 of the first
* channel that failed else (so 1 == first channel failed)
*/
-__EXPORT int rc_calibration_check(void);
+__EXPORT int rc_calibration_check(int mavlink_fd);
__END_DECLS
diff --git a/src/systemcmds/mixer/mixer.c b/src/systemcmds/mixer/mixer.cpp
index e642ed067..6da39d371 100644
--- a/src/systemcmds/mixer/mixer.c
+++ b/src/systemcmds/mixer/mixer.cpp
@@ -47,10 +47,15 @@
#include <nuttx/compiler.h>
#include <systemlib/err.h>
-#include <drivers/drv_mixer.h>
+#include <systemlib/mixer/mixer.h>
#include <uORB/topics/actuator_controls.h>
-__EXPORT int mixer_main(int argc, char *argv[]);
+/**
+ * Mixer utility for loading mixer files to devices
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int mixer_main(int argc, char *argv[]);
static void usage(const char *reason) noreturn_function;
static void load(const char *devname, const char *fname) noreturn_function;
@@ -87,8 +92,6 @@ static void
load(const char *devname, const char *fname)
{
int dev;
- FILE *fp;
- char line[120];
char buf[2048];
/* open the device */
@@ -99,49 +102,7 @@ load(const char *devname, const char *fname)
if (ioctl(dev, MIXERIOCRESET, 0))
err(1, "can't reset mixers on %s", devname);
- /* open the mixer definition file */
- fp = fopen(fname, "r");
- if (fp == NULL)
- err(1, "can't open %s", fname);
-
- /* read valid lines from the file into a buffer */
- buf[0] = '\0';
- for (;;) {
-
- /* get a line, bail on error/EOF */
- line[0] = '\0';
- if (fgets(line, sizeof(line), fp) == NULL)
- break;
-
- /* if the line doesn't look like a mixer definition line, skip it */
- if ((strlen(line) < 2) || !isupper(line[0]) || (line[1] != ':'))
- continue;
-
- /* compact whitespace in the buffer */
- char *t, *f;
- for (f = buf; *f != '\0'; f++) {
- /* scan for space characters */
- if (*f == ' ') {
- /* look for additional spaces */
- t = f + 1;
- while (*t == ' ')
- t++;
- if (*t == '\0') {
- /* strip trailing whitespace */
- *f = '\0';
- } else if (t > (f + 1)) {
- memmove(f + 1, t, strlen(t) + 1);
- }
- }
- }
-
- /* if the line is too long to fit in the buffer, bail */
- if ((strlen(line) + strlen(buf) + 1) >= sizeof(buf))
- break;
-
- /* add the line to the buffer */
- strcat(buf, line);
- }
+ load_mixer_file(fname, &buf[0], sizeof(buf));
/* XXX pass the buffer to the device */
int ret = ioctl(dev, MIXERIOCLOADBUF, (unsigned long)buf);
diff --git a/src/systemcmds/mixer/module.mk b/src/systemcmds/mixer/module.mk
index d5a3f9f77..cdbff75f0 100644
--- a/src/systemcmds/mixer/module.mk
+++ b/src/systemcmds/mixer/module.mk
@@ -36,7 +36,7 @@
#
MODULE_COMMAND = mixer
-SRCS = mixer.c
+SRCS = mixer.cpp
MODULE_STACKSIZE = 4096
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index e9c5f1a2c..1c58a2db6 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -140,7 +140,7 @@ int preflight_check_main(int argc, char *argv[])
/* ---- RC CALIBRATION ---- */
- bool rc_ok = (OK == rc_calibration_check());
+ bool rc_ok = (OK == rc_calibration_check(mavlink_fd));
/* warn */
if (!rc_ok)
@@ -227,4 +227,4 @@ static int led_off(int leds, int led)
static int led_on(int leds, int led)
{
return ioctl(leds, LED_ON, led);
-} \ No newline at end of file
+}
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 754d3a0da..6729ce4ae 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -23,6 +23,7 @@ SRCS = test_adc.c \
test_uart_console.c \
test_uart_loopback.c \
test_uart_send.c \
+ test_mixer.cpp \
tests_file.c \
tests_main.c \
tests_param.c
diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp
new file mode 100644
index 000000000..4da86042d
--- /dev/null
+++ b/src/systemcmds/tests/test_mixer.cpp
@@ -0,0 +1,199 @@
+/****************************************************************************
+ *
+ * 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_mixer.hpp
+ *
+ * Mixer load test
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <string.h>
+#include <time.h>
+
+#include <systemlib/err.h>
+#include <systemlib/mixer/mixer.h>
+
+#include "tests.h"
+
+static int mixer_callback(uintptr_t handle,
+ uint8_t control_group,
+ uint8_t control_index,
+ float &control);
+
+int test_mixer(int argc, char *argv[])
+{
+ warnx("testing mixer");
+
+ char *filename = "/etc/mixers/IO_pass.mix";
+
+ if (argc > 1)
+ filename = argv[1];
+
+ warnx("loading: %s", filename);
+
+ char buf[2048];
+
+ load_mixer_file(filename, &buf[0], sizeof(buf));
+ unsigned loaded = strlen(buf);
+
+ warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded);
+
+ /* load the mixer in chunks, like
+ * in the case of a remote load,
+ * e.g. on PX4IO.
+ */
+
+ unsigned nused = 0;
+
+ const unsigned chunk_size = 64;
+
+ MixerGroup mixer_group(mixer_callback, 0);
+
+ /* load at once test */
+ unsigned xx = loaded;
+ mixer_group.load_from_buf(&buf[0], xx);
+ warnx("complete buffer load: loaded %u mixers", mixer_group.count());
+ if (mixer_group.count() != 8)
+ return 1;
+
+ unsigned empty_load = 2;
+ char empty_buf[2];
+ empty_buf[0] = ' ';
+ empty_buf[1] = '\0';
+ mixer_group.reset();
+ mixer_group.load_from_buf(&empty_buf[0], empty_load);
+ warnx("empty buffer load: loaded %u mixers, used: %u", mixer_group.count(), empty_load);
+ if (empty_load != 0)
+ return 1;
+
+ /* FIRST mark the mixer as invalid */
+ bool mixer_ok = false;
+ /* THEN actually delete it */
+ mixer_group.reset();
+ char mixer_text[256]; /* large enough for one mixer */
+ unsigned mixer_text_length = 0;
+
+ unsigned transmitted = 0;
+
+ warnx("transmitted: %d, loaded: %d", transmitted, loaded);
+
+ while (transmitted < loaded) {
+
+ unsigned text_length = (loaded - transmitted > chunk_size) ? chunk_size : loaded - transmitted;
+
+ /* check for overflow - this would be really fatal */
+ if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
+ bool mixer_ok = false;
+ return 1;
+ }
+
+ /* append mixer text and nul-terminate */
+ memcpy(&mixer_text[mixer_text_length], &buf[transmitted], text_length);
+ mixer_text_length += text_length;
+ mixer_text[mixer_text_length] = '\0';
+ warnx("buflen %u, text:\n\"%s\"", mixer_text_length, &mixer_text[0]);
+
+ /* process the text buffer, adding new mixers as their descriptions can be parsed */
+ unsigned resid = mixer_text_length;
+ mixer_group.load_from_buf(&mixer_text[0], resid);
+
+ /* if anything was parsed */
+ if (resid != mixer_text_length) {
+
+ /* only set mixer ok if no residual is left over */
+ if (resid == 0) {
+ mixer_ok = true;
+ } else {
+ /* not yet reached the end of the mixer, set as not ok */
+ mixer_ok = false;
+ }
+
+ warnx("used %u", mixer_text_length - resid);
+
+ /* copy any leftover text to the base of the buffer for re-use */
+ if (resid > 0)
+ memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid);
+
+ mixer_text_length = resid;
+ }
+
+ transmitted += text_length;
+ }
+
+ warnx("chunked load: loaded %u mixers", mixer_group.count());
+
+ if (mixer_group.count() != 8)
+ return 1;
+
+ /* load multirotor at once test */
+ mixer_group.reset();
+
+ if (argc > 2)
+ filename = argv[2];
+ else
+ filename = "/etc/mixers/FMU_quad_w.mix";
+
+ load_mixer_file(filename, &buf[0], sizeof(buf));
+ loaded = strlen(buf);
+
+ warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded);
+
+ unsigned mc_loaded = loaded;
+ mixer_group.load_from_buf(&buf[0], mc_loaded);
+ warnx("complete buffer load: loaded %u mixers", mixer_group.count());
+ if (mixer_group.count() != 8)
+ return 1;
+}
+
+static int
+mixer_callback(uintptr_t handle,
+ uint8_t control_group,
+ uint8_t control_index,
+ float &control)
+{
+ if (control_group != 0)
+ return -1;
+
+ control = 0.0f;
+
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index c02ea6808..c483108cf 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -76,6 +76,8 @@
* Public Function Prototypes
****************************************************************************/
+__BEGIN_DECLS
+
extern int test_sensors(int argc, char *argv[]);
extern int test_gpio(int argc, char *argv[]);
extern int test_hrt(int argc, char *argv[]);
@@ -98,5 +100,8 @@ extern int test_jig_voltages(int argc, char *argv[]);
extern int test_param(int argc, char *argv[]);
extern int test_bson(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);
+extern int test_mixer(int argc, char *argv[]);
+
+__END_DECLS
#endif /* __APPS_PX4_TESTS_H */
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 9f8c5c9ea..9eb9c632e 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -110,6 +110,7 @@ const struct {
{"param", test_param, 0},
{"bson", test_bson, 0},
{"file", test_file, 0},
+ {"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};