aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-03-12 20:38:39 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-03-12 20:38:39 +0100
commit89e6b3f60621eb1b60dc58b60ea3c7c01dfb11cc (patch)
tree7f14acb4bbc67b641e4212a7685990278ab10217
parentd69d895f0240a0dda5fda2f8f046179b069439a4 (diff)
parentf5b21fbcde2b439ccdbd7f824adeea6ec78ea0b5 (diff)
downloadpx4-firmware-89e6b3f60621eb1b60dc58b60ea3c7c01dfb11cc.tar.gz
px4-firmware-89e6b3f60621eb1b60dc58b60ea3c7c01dfb11cc.tar.bz2
px4-firmware-89e6b3f60621eb1b60dc58b60ea3c7c01dfb11cc.zip
Merge branch 'master' of github.com:PX4/Firmware into laser_rangefinder
-rw-r--r--Tools/fetch_log.py133
-rw-r--r--Tools/px_romfs_pruner.py83
-rw-r--r--makefiles/config_px4fmu-v1_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_default.mk2
-rw-r--r--makefiles/firmware.mk4
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig6
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.cpp17
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.h11
-rw-r--r--src/lib/launchdetection/LaunchDetector.cpp18
-rw-r--r--src/lib/launchdetection/LaunchDetector.h9
-rw-r--r--src/lib/launchdetection/LaunchMethod.h7
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp3
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp56
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c10
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp11
-rw-r--r--src/modules/gpio_led/gpio_led.c80
-rw-r--r--src/modules/navigator/geofence.cpp11
-rw-r--r--src/modules/navigator/geofence.h6
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.c5
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
-rw-r--r--src/modules/sdlog2/logbuffer.c3
-rw-r--r--src/modules/sdlog2/sdlog2.c885
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h14
-rw-r--r--src/systemcmds/dumpfile/dumpfile.c116
-rw-r--r--src/systemcmds/dumpfile/module.mk41
25 files changed, 923 insertions, 611 deletions
diff --git a/Tools/fetch_log.py b/Tools/fetch_log.py
new file mode 100644
index 000000000..edcc6557c
--- /dev/null
+++ b/Tools/fetch_log.py
@@ -0,0 +1,133 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Log fetcher
+#
+# Print list of logs:
+# python fetch_log.py
+#
+# Fetch log:
+# python fetch_log.py sess001/log001.bin
+#
+
+import serial, time, sys, os
+
+def wait_for_string(ser, s, timeout=1.0, debug=False):
+ t0 = time.time()
+ buf = []
+ res = []
+ n = 0
+ while (True):
+ c = ser.read()
+ if debug:
+ sys.stderr.write(c)
+ buf.append(c)
+ if len(buf) > len(s):
+ res.append(buf.pop(0))
+ n += 1
+ if n % 10000 == 0:
+ sys.stderr.write(str(n) + "\n")
+ if "".join(buf) == s:
+ break
+ if timeout > 0.0 and time.time() - t0 > timeout:
+ raise Exception("Timeout while waiting for: " + s)
+ return "".join(res)
+
+def exec_cmd(ser, cmd, timeout):
+ ser.write(cmd + "\n")
+ ser.flush()
+ wait_for_string(ser, cmd + "\r\n", timeout)
+ return wait_for_string(ser, "nsh> \x1b[K", timeout)
+
+def ls_dir(ser, dir, timeout=1.0):
+ res = []
+ for line in exec_cmd(ser, "ls -l " + dir, timeout).splitlines()[1:]:
+ res.append((line[20:], int(line[11:19].strip()), line[1] == "d"))
+ return res
+
+def list_logs(ser):
+ logs_dir = "/fs/microsd/log"
+ res = []
+ for d in ls_dir(ser, logs_dir):
+ if d[2]:
+ sess_dir = d[0][:-1]
+ for f in ls_dir(ser, logs_dir + "/" + sess_dir):
+ log_file = f[0]
+ log_size = f[1]
+ res.append(sess_dir + "/" + log_file + "\t" + str(log_size))
+ return "\n".join(res)
+
+def fetch_log(ser, fn, timeout):
+ cmd = "dumpfile " + fn
+ ser.write(cmd + "\n")
+ ser.flush()
+ wait_for_string(ser, cmd + "\r\n", timeout, True)
+ res = wait_for_string(ser, "\n", timeout, True)
+ data = []
+ if res.startswith("OK"):
+ size = int(res.split()[1])
+ n = 0
+ print "Reading data:"
+ while (n < size):
+ buf = ser.read(min(size - n, 8192))
+ data.append(buf)
+ n += len(buf)
+ sys.stdout.write(".")
+ sys.stdout.flush()
+ print
+ else:
+ raise Exception("Error reading log")
+ wait_for_string(ser, "nsh> \x1b[K", timeout)
+ return "".join(data)
+
+def main():
+ dev = "/dev/tty.usbmodem1"
+ ser = serial.Serial(dev, "115200", timeout=0.2)
+ if len(sys.argv) < 2:
+ print list_logs(ser)
+ else:
+ log_file = sys.argv[1]
+ data = fetch_log(ser, "/fs/microsd/log/" + log_file, 1.0)
+ try:
+ os.mkdir(log_file.split("/")[0])
+ except:
+ pass
+ fout = open(log_file, "wb")
+ fout.write(data)
+ fout.close()
+ ser.close()
+
+if __name__ == "__main__":
+ main()
diff --git a/Tools/px_romfs_pruner.py b/Tools/px_romfs_pruner.py
new file mode 100644
index 000000000..ceef9f9be
--- /dev/null
+++ b/Tools/px_romfs_pruner.py
@@ -0,0 +1,83 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2014 PX4 Development Team. All rights reserved.
+# Author: Julian Oes <joes@student.ethz.ch>
+
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+
+"""
+px_romfs_pruner.py:
+Delete all comments and newlines before ROMFS is converted to an image
+"""
+
+from __future__ import print_function
+import argparse
+import os
+
+def main():
+
+ # Parse commandline arguments
+ parser = argparse.ArgumentParser(description="ROMFS pruner.")
+ parser.add_argument('--folder', action="store", help="ROMFS scratch folder.")
+ args = parser.parse_args()
+
+ print("Pruning ROMFS files.")
+
+ # go through
+ for (root, dirs, files) in os.walk(args.folder):
+ for file in files:
+ # only prune text files
+ if ".zip" in file or ".bin" in file:
+ continue
+
+ file_path = os.path.join(root, file)
+
+ # read file line by line
+ pruned_content = ""
+ with open(file_path, "r") as f:
+ for line in f:
+
+ # handle mixer files differently than startup files
+ if file_path.endswith(".mix"):
+ if line.startswith(("Z:", "M:", "R: ", "O:", "S:")):
+ pruned_content += line
+ else:
+ if not line.isspace() and not line.strip().startswith("#"):
+ pruned_content += line
+
+ # overwrite old scratch file
+ with open(file_path, "w") as f:
+ f.write(pruned_content)
+
+
+if __name__ == '__main__':
+ main() \ No newline at end of file
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index aff614cbb..651c2ac38 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -56,6 +56,7 @@ MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/hw_ver
+MODULES += systemcmds/dumpfile
#
# General system control
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index aac5beeb1..c80bc741d 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -64,6 +64,7 @@ MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/mtd
MODULES += systemcmds/hw_ver
+MODULES += systemcmds/dumpfile
#
# General system control
@@ -72,6 +73,7 @@ MODULES += modules/commander
MODULES += modules/navigator
MODULES += modules/mavlink
MODULES += modules/mavlink_onboard
+MODULES += modules/gpio_led
#
# Estimation modules (EKF/ SO3 / other filters)
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index cb20d9cd1..1b646d9e0 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -355,6 +355,9 @@ ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
LIBS += $(ROMFS_OBJ)
LINK_DEPS += $(ROMFS_OBJ)
+# Remove all comments from startup and mixer files
+ROMFS_PRUNER = $(PX4_BASE)/Tools/px_romfs_pruner.py
+
# Turn the ROMFS image into an object file
$(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
$(call BIN_TO_OBJ,$<,$@,romfs_img)
@@ -372,6 +375,7 @@ ifneq ($(ROMFS_EXTRA_FILES),)
$(Q) $(MKDIR) -p $(ROMFS_SCRATCH)/extras
$(Q) $(COPY) $(ROMFS_EXTRA_FILES) $(ROMFS_SCRATCH)/extras
endif
+ $(Q) $(PYTHON) -u $(ROMFS_PRUNER) --folder $(ROMFS_SCRATCH)
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index 1dc96b3c3..20edc68aa 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -417,7 +417,7 @@ CONFIG_PREALLOC_TIMERS=50
#
# Stack and heap information
#
-CONFIG_IDLETHREAD_STACKSIZE=6000
+CONFIG_IDLETHREAD_STACKSIZE=4096
CONFIG_USERMAIN_STACKSIZE=4096
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=2048
@@ -720,11 +720,11 @@ CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
-CONFIG_SCHED_WORKSTACKSIZE=4000
+CONFIG_SCHED_WORKSTACKSIZE=2048
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=4000
+CONFIG_SCHED_LPWORKSTACKSIZE=2048
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.cpp b/src/lib/launchdetection/CatapultLaunchMethod.cpp
index 1039b4a09..12f80c4a3 100644
--- a/src/lib/launchdetection/CatapultLaunchMethod.cpp
+++ b/src/lib/launchdetection/CatapultLaunchMethod.cpp
@@ -41,12 +41,16 @@
#include "CatapultLaunchMethod.h"
#include <systemlib/err.h>
-CatapultLaunchMethod::CatapultLaunchMethod() :
+namespace launchdetection
+{
+
+CatapultLaunchMethod::CatapultLaunchMethod(SuperBlock *parent) :
+ SuperBlock(parent, "CAT"),
last_timestamp(hrt_absolute_time()),
integrator(0.0f),
launchDetected(false),
- threshold_accel(NULL, "LAUN_CAT_A", false),
- threshold_time(NULL, "LAUN_CAT_T", false)
+ threshold_accel(this, "A"),
+ threshold_time(this, "T")
{
}
@@ -83,14 +87,11 @@ bool CatapultLaunchMethod::getLaunchDetected()
return launchDetected;
}
-void CatapultLaunchMethod::updateParams()
-{
- threshold_accel.update();
- threshold_time.update();
-}
void CatapultLaunchMethod::reset()
{
integrator = 0.0f;
launchDetected = false;
}
+
+}
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.h b/src/lib/launchdetection/CatapultLaunchMethod.h
index b8476b4c8..55c46ff3f 100644
--- a/src/lib/launchdetection/CatapultLaunchMethod.h
+++ b/src/lib/launchdetection/CatapultLaunchMethod.h
@@ -44,17 +44,20 @@
#include "LaunchMethod.h"
#include <drivers/drv_hrt.h>
+#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
-class CatapultLaunchMethod : public LaunchMethod
+namespace launchdetection
+{
+
+class CatapultLaunchMethod : public LaunchMethod, public control::SuperBlock
{
public:
- CatapultLaunchMethod();
+ CatapultLaunchMethod(SuperBlock *parent);
~CatapultLaunchMethod();
void update(float accel_x);
bool getLaunchDetected();
- void updateParams();
void reset();
private:
@@ -68,3 +71,5 @@ private:
};
#endif /* CATAPULTLAUNCHMETHOD_H_ */
+
+}
diff --git a/src/lib/launchdetection/LaunchDetector.cpp b/src/lib/launchdetection/LaunchDetector.cpp
index 4109a90ba..bf539701b 100644
--- a/src/lib/launchdetection/LaunchDetector.cpp
+++ b/src/lib/launchdetection/LaunchDetector.cpp
@@ -42,12 +42,16 @@
#include "CatapultLaunchMethod.h"
#include <systemlib/err.h>
+namespace launchdetection
+{
+
LaunchDetector::LaunchDetector() :
- launchdetection_on(NULL, "LAUN_ALL_ON", false),
- throttlePreTakeoff(NULL, "LAUN_THR_PRE", false)
+ SuperBlock(NULL, "LAUN"),
+ launchdetection_on(this, "ALL_ON"),
+ throttlePreTakeoff(this, "THR_PRE")
{
/* init all detectors */
- launchMethods[0] = new CatapultLaunchMethod();
+ launchMethods[0] = new CatapultLaunchMethod(this);
/* update all parameters of all detectors */
@@ -87,12 +91,4 @@ bool LaunchDetector::getLaunchDetected()
return false;
}
-void LaunchDetector::updateParams() {
-
- launchdetection_on.update();
- throttlePreTakeoff.update();
-
- for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
- launchMethods[i]->updateParams();
- }
}
diff --git a/src/lib/launchdetection/LaunchDetector.h b/src/lib/launchdetection/LaunchDetector.h
index 05708c526..8066ebab3 100644
--- a/src/lib/launchdetection/LaunchDetector.h
+++ b/src/lib/launchdetection/LaunchDetector.h
@@ -45,10 +45,13 @@
#include <stdint.h>
#include "LaunchMethod.h"
-
+#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
-class __EXPORT LaunchDetector
+namespace launchdetection
+{
+
+class __EXPORT LaunchDetector : public control::SuperBlock
{
public:
LaunchDetector();
@@ -57,7 +60,6 @@ public:
void update(float accel_x);
bool getLaunchDetected();
- void updateParams();
bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
@@ -72,5 +74,6 @@ private:
};
+}
#endif // LAUNCHDETECTOR_H
diff --git a/src/lib/launchdetection/LaunchMethod.h b/src/lib/launchdetection/LaunchMethod.h
index 0cfbab3e0..01fa7050e 100644
--- a/src/lib/launchdetection/LaunchMethod.h
+++ b/src/lib/launchdetection/LaunchMethod.h
@@ -41,15 +41,20 @@
#ifndef LAUNCHMETHOD_H_
#define LAUNCHMETHOD_H_
+namespace launchdetection
+{
+
class LaunchMethod
{
public:
virtual void update(float accel_x) = 0;
virtual bool getLaunchDetected() = 0;
- virtual void updateParams() = 0;
virtual void reset() = 0;
+
protected:
private:
};
+}
+
#endif /* LAUNCHMETHOD_H_ */
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 620185fb7..00bd23f83 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -477,6 +477,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
dt = 0.005f;
parameters_update(&ekf_param_handles, &ekf_params);
+ /* update mag declination rotation matrix */
+ R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl);
+
x_aposteriori_k[0] = z_k[0];
x_aposteriori_k[1] = z_k[1];
x_aposteriori_k[2] = z_k[2];
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 17b1028f9..5ade835ff 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -166,6 +166,15 @@ private:
float airspeed_min;
float airspeed_trim;
float airspeed_max;
+
+ float trim_roll;
+ float trim_pitch;
+ float trim_yaw;
+ float rollsp_offset_deg; /**< Roll Setpoint Offset in deg */
+ float pitchsp_offset_deg; /**< Pitch Setpoint Offset in deg */
+ float rollsp_offset_rad; /**< Roll Setpoint Offset in rad */
+ float pitchsp_offset_rad; /**< Pitch Setpoint Offset in rad */
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -197,6 +206,12 @@ private:
param_t airspeed_min;
param_t airspeed_trim;
param_t airspeed_max;
+
+ param_t trim_roll;
+ param_t trim_pitch;
+ param_t trim_yaw;
+ param_t rollsp_offset_deg;
+ param_t pitchsp_offset_deg;
} _parameter_handles; /**< handles for interesting parameters */
@@ -335,6 +350,12 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_parameter_handles.y_coordinated_min_speed = param_find("FW_YCO_VMIN");
+ _parameter_handles.trim_roll = param_find("TRIM_ROLL");
+ _parameter_handles.trim_pitch = param_find("TRIM_PITCH");
+ _parameter_handles.trim_yaw = param_find("TRIM_YAW");
+ _parameter_handles.rollsp_offset_deg = param_find("FW_RSP_OFF");
+ _parameter_handles.pitchsp_offset_deg = param_find("FW_PSP_OFF");
+
/* fetch initial parameter values */
parameters_update();
}
@@ -395,6 +416,15 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
param_get(_parameter_handles.airspeed_max, &(_parameters.airspeed_max));
+ param_get(_parameter_handles.trim_roll, &(_parameters.trim_roll));
+ param_get(_parameter_handles.trim_pitch, &(_parameters.trim_pitch));
+ param_get(_parameter_handles.trim_yaw, &(_parameters.trim_yaw));
+ param_get(_parameter_handles.rollsp_offset_deg, &(_parameters.rollsp_offset_deg));
+ param_get(_parameter_handles.pitchsp_offset_deg, &(_parameters.pitchsp_offset_deg));
+ _parameters.rollsp_offset_rad = math::radians(_parameters.rollsp_offset_deg);
+ _parameters.pitchsp_offset_rad = math::radians(_parameters.pitchsp_offset_deg);
+
+
/* pitch control parameters */
_pitch_ctrl.set_time_constant(_parameters.tconst);
_pitch_ctrl.set_k_p(_parameters.p_p);
@@ -648,13 +678,13 @@ FixedwingAttitudeControl::task_main()
float airspeed_scaling = _parameters.airspeed_trim / airspeed;
//warnx("aspd scale: %6.2f act scale: %6.2f", airspeed_scaling, actuator_scaling);
- float roll_sp = 0.0f;
- float pitch_sp = 0.0f;
+ float roll_sp = _parameters.rollsp_offset_rad;
+ float pitch_sp = _parameters.pitchsp_offset_rad;
float throttle_sp = 0.0f;
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
- roll_sp = _att_sp.roll_body;
- pitch_sp = _att_sp.pitch_body;
+ roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
+ pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
throttle_sp = _att_sp.thrust;
/* reset integrals where needed */
@@ -670,9 +700,13 @@ FixedwingAttitudeControl::task_main()
* With this mapping the stick angle is a 1:1 representation of
* the commanded attitude. If more than 45 degrees are desired,
* a scaling parameter can be applied to the remote.
+ *
+ * The trim gets subtracted here from the manual setpoint to get
+ * the intended attitude setpoint. Later, after the rate control step the
+ * trim is added again to the control signal.
*/
- roll_sp = _manual.roll * 0.75f;
- pitch_sp = _manual.pitch * 0.75f;
+ roll_sp = (_manual.roll - _parameters.trim_roll) * 0.75f + _parameters.rollsp_offset_rad;
+ pitch_sp = (_manual.pitch - _parameters.trim_pitch) * 0.75f + _parameters.pitchsp_offset_rad;
throttle_sp = _manual.throttle;
_actuators.control[4] = _manual.flaps;
@@ -685,7 +719,7 @@ FixedwingAttitudeControl::task_main()
att_sp.timestamp = hrt_absolute_time();
att_sp.roll_body = roll_sp;
att_sp.pitch_body = pitch_sp;
- att_sp.yaw_body = 0.0f;
+ att_sp.yaw_body = 0.0f - _parameters.trim_yaw;
att_sp.thrust = throttle_sp;
/* lazily publish the setpoint only once available */
@@ -719,12 +753,12 @@ FixedwingAttitudeControl::task_main()
speed_body_u, speed_body_v, speed_body_w,
_roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate()); //runs last, because is depending on output of roll and pitch attitude
- /* Run attitude RATE controllers which need the desired attitudes from above */
+ /* Run attitude RATE controllers which need the desired attitudes from above, add trim */
float roll_u = _roll_ctrl.control_bodyrate(_att.pitch,
_att.rollspeed, _att.yawspeed,
_yaw_ctrl.get_desired_rate(),
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
- _actuators.control[0] = (isfinite(roll_u)) ? roll_u : 0.0f;
+ _actuators.control[0] = (isfinite(roll_u)) ? roll_u + _parameters.trim_roll : _parameters.trim_roll;
if (!isfinite(roll_u)) {
warnx("roll_u %.4f", roll_u);
}
@@ -733,7 +767,7 @@ FixedwingAttitudeControl::task_main()
_att.pitchspeed, _att.yawspeed,
_yaw_ctrl.get_desired_rate(),
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
- _actuators.control[1] = (isfinite(pitch_u)) ? pitch_u : 0.0f;
+ _actuators.control[1] = (isfinite(pitch_u)) ? pitch_u + _parameters.trim_pitch : _parameters.trim_pitch;
if (!isfinite(pitch_u)) {
warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f, airspeed %.4f, airspeed_scaling %.4f, roll_sp %.4f, pitch_sp %.4f, _roll_ctrl.get_desired_rate() %.4f, _pitch_ctrl.get_desired_rate() %.4f att_sp.roll_body %.4f",
pitch_u, _yaw_ctrl.get_desired_rate(), airspeed, airspeed_scaling, roll_sp, pitch_sp, _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate(), _att_sp.roll_body);
@@ -743,7 +777,7 @@ FixedwingAttitudeControl::task_main()
_att.pitchspeed, _att.yawspeed,
_pitch_ctrl.get_desired_rate(),
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
- _actuators.control[2] = (isfinite(yaw_u)) ? yaw_u : 0.0f;
+ _actuators.control[2] = (isfinite(yaw_u)) ? yaw_u + _parameters.trim_yaw : _parameters.trim_yaw;
if (!isfinite(yaw_u)) {
warnx("yaw_u %.4f", yaw_u);
}
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
index 1c615094c..c80a44f2a 100644
--- a/src/modules/fw_att_control/fw_att_control_params.c
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -176,3 +176,13 @@ PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 20.0f);
// @Description If the airspeed is above this value the TECS controller will try to decrease airspeed more aggressively
// @Range 0.0 to 30
PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 50.0f);
+
+// @DisplayName Roll Setpoint Offset
+// @Description An airframe specific offset of the roll setpoint in degrees, the value is added to the roll setpoint and should correspond to the typical cruise speed of the airframe
+// @Range -90.0 to 90.0
+PARAM_DEFINE_FLOAT(FW_RSP_OFF, 0.0f);
+
+// @DisplayName Pitch Setpoint Offset
+// @Description An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the typical cruise speed of the airframe
+// @Range -90.0 to 90.0
+PARAM_DEFINE_FLOAT(FW_PSP_OFF, 0.0f);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 774758ef4..7f13df785 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -186,7 +186,7 @@ private:
float target_bearing;
/* Launch detection */
- LaunchDetector launchDetector;
+ launchdetection::LaunchDetector launchDetector;
/* throttle and airspeed states */
float _airspeed_error; ///< airspeed error to setpoint in m/s
@@ -350,12 +350,12 @@ private:
/*
* Reset takeoff state
*/
- int reset_takeoff_state();
+ void reset_takeoff_state();
/*
* Reset landing state
*/
- int reset_landing_state();
+ void reset_landing_state();
};
namespace l1_control
@@ -989,6 +989,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else {
/* no takeoff detection --> fly */
launch_detected = true;
+ warnx("launchdetection off");
}
}
@@ -1311,14 +1312,14 @@ FixedwingPositionControl::task_main()
_exit(0);
}
-int FixedwingPositionControl::reset_takeoff_state()
+void FixedwingPositionControl::reset_takeoff_state()
{
launch_detected = false;
usePreTakeoffThrust = false;
launchDetector.reset();
}
-int FixedwingPositionControl::reset_landing_state()
+void FixedwingPositionControl::reset_landing_state()
{
land_noreturn_horizontal = false;
land_noreturn_vertical = false;
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index d383146f9..f5f3dea76 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -51,7 +51,6 @@
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/actuator_armed.h>
#include <poll.h>
#include <drivers/drv_gpio.h>
#include <modules/px4iofirmware/protocol.h>
@@ -63,8 +62,6 @@ struct gpio_led_s {
int pin;
struct vehicle_status_s status;
int vehicle_status_sub;
- struct actuator_armed_s armed;
- int actuator_armed_sub;
bool led_state;
int counter;
};
@@ -81,6 +78,7 @@ void gpio_led_cycle(FAR void *arg);
int gpio_led_main(int argc, char *argv[])
{
if (argc < 2) {
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
errx(1, "usage: gpio_led {start|stop} [-p <1|2|a1|a2|r1|r2>]\n"
"\t-p\tUse pin:\n"
"\t\t1\tPX4FMU GPIO_EXT1 (default)\n"
@@ -88,7 +86,15 @@ int gpio_led_main(int argc, char *argv[])
"\t\ta1\tPX4IO ACC1\n"
"\t\ta2\tPX4IO ACC2\n"
"\t\tr1\tPX4IO RELAY1\n"
- "\t\tr2\tPX4IO RELAY2");
+ "\t\tr2\tPX4IO RELAY2"
+ );
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ errx(1, "usage: gpio_led {start|stop} [-p <n>]\n"
+ "\t-p\tUse pin:\n"
+ "\t\tn\tAUX OUT pin number (default: 1)\n"
+ );
+#endif
} else {
@@ -98,10 +104,14 @@ int gpio_led_main(int argc, char *argv[])
}
bool use_io = false;
- int pin = GPIO_EXT_1;
+
+ /* by default use GPIO_EXT_1 on FMUv1 and GPIO_SERVO_1 on FMUv2 */
+ int pin = 1;
if (argc > 2) {
if (!strcmp(argv[2], "-p")) {
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
if (!strcmp(argv[3], "1")) {
use_io = false;
pin = GPIO_EXT_1;
@@ -129,6 +139,20 @@ int gpio_led_main(int argc, char *argv[])
} else {
errx(1, "unsupported pin: %s", argv[3]);
}
+
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ unsigned int n = strtoul(argv[3], NULL, 10);
+
+ if (n >= 1 && n <= 6) {
+ use_io = false;
+ pin = n;
+
+ } else {
+ errx(1, "unsupported pin: %s", argv[3]);
+ }
+
+#endif
}
}
@@ -144,6 +168,8 @@ int gpio_led_main(int argc, char *argv[])
gpio_led_started = true;
char pin_name[24];
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
if (use_io) {
if (pin & (PX4IO_P_SETUP_RELAYS_ACC1 | PX4IO_P_SETUP_RELAYS_ACC2)) {
sprintf(pin_name, "PX4IO ACC%i", (pin >> 3));
@@ -154,9 +180,13 @@ int gpio_led_main(int argc, char *argv[])
} else {
sprintf(pin_name, "PX4FMU GPIO_EXT%i", pin);
-
}
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ sprintf(pin_name, "AUX OUT %i", pin);
+#endif
+
warnx("start, using pin: %s", pin_name);
}
@@ -186,6 +216,7 @@ void gpio_led_start(FAR void *arg)
if (priv->use_io) {
gpio_dev = PX4IO_DEVICE_PATH;
+
} else {
gpio_dev = PX4FMU_DEVICE_PATH;
}
@@ -204,8 +235,10 @@ void gpio_led_start(FAR void *arg)
/* px4fmu only, px4io doesn't support GPIO_SET_OUTPUT and will ignore */
ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, priv->pin);
- /* subscribe to vehicle status topic */
+ /* initialize vehicle status structure */
memset(&priv->status, 0, sizeof(priv->status));
+
+ /* subscribe to vehicle status topic */
priv->vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
/* add worker to queue */
@@ -224,38 +257,32 @@ void gpio_led_cycle(FAR void *arg)
FAR struct gpio_led_s *priv = (FAR struct gpio_led_s *)arg;
/* check for status updates*/
- bool status_updated;
- orb_check(priv->vehicle_status_sub, &status_updated);
+ bool updated;
+ orb_check(priv->vehicle_status_sub, &updated);
- if (status_updated)
+ if (updated)
orb_copy(ORB_ID(vehicle_status), priv->vehicle_status_sub, &priv->status);
- orb_check(priv->vehicle_status_sub, &status_updated);
-
- if (status_updated)
- orb_copy(ORB_ID(actuator_armed), priv->actuator_armed_sub, &priv->armed);
-
/* select pattern for current status */
int pattern = 0;
- if (priv->armed.armed) {
- if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
+ if (priv->status.arming_state == ARMING_STATE_ARMED_ERROR) {
+ pattern = 0x2A; // *_*_*_ fast blink (armed, error)
+
+ } else if (priv->status.arming_state == ARMING_STATE_ARMED) {
+ if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE && priv->status.failsafe_state == FAILSAFE_STATE_NORMAL) {
pattern = 0x3f; // ****** solid (armed)
} else {
- pattern = 0x2A; // *_*_*_ fast blink (armed, battery warning)
+ pattern = 0x3e; // *****_ slow blink (armed, battery low or failsafe)
}
- } else {
- if (priv->armed.ready_to_arm) {
- pattern = 0x00; // ______ off (disarmed, preflight check)
+ } else if (priv->status.arming_state == ARMING_STATE_STANDBY) {
+ pattern = 0x38; // ***___ slow blink (disarmed, ready)
- } else if (priv->armed.ready_to_arm && priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
- pattern = 0x38; // ***___ slow blink (disarmed, ready)
+ } else if (priv->status.arming_state == ARMING_STATE_STANDBY_ERROR) {
+ pattern = 0x28; // *_*___ slow double blink (disarmed, error)
- } else {
- pattern = 0x28; // *_*___ slow double blink (disarmed, not good to arm)
- }
}
/* blink pattern */
@@ -266,6 +293,7 @@ void gpio_led_cycle(FAR void *arg)
if (led_state_new) {
ioctl(priv->gpio_fd, GPIO_SET, priv->pin);
+
} else {
ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin);
}
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index 9bbaf167a..f452a85f7 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -55,11 +55,13 @@
#endif
static const int ERROR = -1;
-Geofence::Geofence() : _fence_pub(-1),
+Geofence::Geofence() :
+ SuperBlock(NULL, "GF"),
+ _fence_pub(-1),
_altitude_min(0),
_altitude_max(0),
_verticesCount(0),
- param_geofence_on(NULL, "GF_ON", false)
+ param_geofence_on(this, "ON")
{
/* Load initial params */
updateParams();
@@ -292,8 +294,3 @@ int Geofence::clearDm()
{
dm_clear(DM_KEY_FENCE_POINTS);
}
-
-void Geofence::updateParams()
-{
- param_geofence_on.update();
-}
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
index 5b56ebc7a..9628b7271 100644
--- a/src/modules/navigator/geofence.h
+++ b/src/modules/navigator/geofence.h
@@ -41,11 +41,13 @@
#define GEOFENCE_H_
#include <uORB/topics/fence.h>
+#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#define GEOFENCE_FILENAME "/fs/microsd/etc/geofence.txt"
-class Geofence {
+class Geofence : public control::SuperBlock
+{
private:
orb_advert_t _fence_pub; /**< publish fence topic */
@@ -85,8 +87,6 @@ public:
int loadFromFile(const char *filename);
bool isEmpty() {return _verticesCount == 0;}
-
- void updateParams();
};
diff --git a/src/modules/position_estimator_inav/inertial_filter.c b/src/modules/position_estimator_inav/inertial_filter.c
index 13328edb4..7cd076948 100644
--- a/src/modules/position_estimator_inav/inertial_filter.c
+++ b/src/modules/position_estimator_inav/inertial_filter.c
@@ -15,10 +15,7 @@ void inertial_filter_predict(float dt, float x[3])
void inertial_filter_correct(float e, float dt, float x[3], int i, float w)
{
- float ewdt = w * dt;
- if (ewdt > 1.0f)
- ewdt = 1.0f; // prevent over-correcting
- ewdt *= e;
+ float ewdt = e * w * dt;
x[i] += ewdt;
if (i == 0) {
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index d6d03367b..a14354138 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -623,7 +623,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
float dt = t_prev > 0 ? (t - t_prev) / 1000000.0f : 0.0f;
- dt = fmaxf(fminf(0.02, dt), 0.005);
+ dt = fmaxf(fminf(0.02, dt), 0.002); // constrain dt from 2 to 20 ms
t_prev = t;
/* use GPS if it's valid and reference position initialized */
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
index 6a29d7e5c..2da67d8a9 100644
--- a/src/modules/sdlog2/logbuffer.c
+++ b/src/modules/sdlog2/logbuffer.c
@@ -74,8 +74,9 @@ bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size)
// bytes available to write
int available = lb->read_ptr - lb->write_ptr - 1;
- if (available < 0)
+ if (available < 0) {
available += lb->size;
+ }
if (size > available) {
// buffer overflow
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 1365d9e70..ad3a7f12c 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -134,12 +134,6 @@ static uint64_t gps_time = 0;
/* current state of logging */
static bool logging_enabled = false;
-/* enable logging on start (-e option) */
-static bool log_on_start = false;
-/* enable logging when armed (-a option) */
-static bool log_when_armed = false;
-/* delay = 1 / rate (rate defined by -r option) */
-static useconds_t sleep_delay = 0;
/* use date/time for naming directories and files (-t option) */
static bool log_name_timestamp = false;
@@ -159,6 +153,8 @@ static void *logwriter_thread(void *arg);
*/
__EXPORT int sdlog2_main(int argc, char *argv[]);
+static bool copy_if_updated(orb_id_t topic, int handle, void *buffer);
+
/**
* Mainloop of sd log deamon.
*/
@@ -220,8 +216,9 @@ static int open_log_file(void);
static void
sdlog2_usage(const char *reason)
{
- if (reason)
+ if (reason) {
fprintf(stderr, "%s\n", reason);
+ }
errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
@@ -241,8 +238,9 @@ sdlog2_usage(const char *reason)
*/
int sdlog2_main(int argc, char *argv[])
{
- if (argc < 2)
+ if (argc < 2) {
sdlog2_usage("missing command");
+ }
if (!strcmp(argv[1], "start")) {
@@ -401,22 +399,29 @@ static void *logwriter_thread(void *arg)
int log_fd = open_log_file();
- if (log_fd < 0)
- return;
+ if (log_fd < 0) {
+ return NULL;
+ }
struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
/* write log messages formats, version and parameters */
log_bytes_written += write_formats(log_fd);
+
log_bytes_written += write_version(log_fd);
+
log_bytes_written += write_parameters(log_fd);
+
fsync(log_fd);
int poll_count = 0;
void *read_ptr;
+
int n = 0;
+
bool should_wait = false;
+
bool is_part = false;
while (true) {
@@ -449,7 +454,6 @@ static void *logwriter_thread(void *arg)
n = available;
}
- lseek(log_fd, 0, SEEK_CUR);
n = write(log_fd, read_ptr, n);
should_wait = (n == available) && !is_part;
@@ -483,7 +487,7 @@ static void *logwriter_thread(void *arg)
fsync(log_fd);
close(log_fd);
- return;
+ return NULL;
}
void sdlog2_start_log()
@@ -628,6 +632,19 @@ int write_parameters(int fd)
return written;
}
+bool copy_if_updated(orb_id_t topic, int handle, void *buffer)
+{
+ bool updated;
+
+ orb_check(handle, &updated);
+
+ if (updated) {
+ orb_copy(topic, handle, buffer);
+ }
+
+ return updated;
+}
+
int sdlog2_thread_main(int argc, char *argv[])
{
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
@@ -636,12 +653,14 @@ int sdlog2_thread_main(int argc, char *argv[])
warnx("failed to open MAVLink log stream, start mavlink app first");
}
- /* log buffer size */
+ /* delay = 1 / rate (rate defined by -r option), default log rate: 50 Hz */
+ useconds_t sleep_delay = 20000;
int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
-
logging_enabled = false;
- log_on_start = false;
- log_when_armed = false;
+ /* enable logging on start (-e option) */
+ bool log_on_start = false;
+ /* enable logging when armed (-a option) */
+ bool log_when_armed = false;
log_name_timestamp = false;
flag_system_armed = false;
@@ -651,17 +670,20 @@ int sdlog2_thread_main(int argc, char *argv[])
argv += 2;
int ch;
+ /* don't exit from getopt loop to leave getopt global variables in consistent state,
+ * set error flag instead */
+ bool err_flag = false;
+
while ((ch = getopt(argc, argv, "r:b:eat")) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(optarg, NULL, 10);
- if (r == 0) {
- sleep_delay = 0;
-
- } else {
- sleep_delay = 1000000 / r;
+ if (r <= 0) {
+ r = 1;
}
+
+ sleep_delay = 1000000 / r;
}
break;
@@ -698,20 +720,27 @@ int sdlog2_thread_main(int argc, char *argv[])
} else {
warnx("unknown option character `\\x%x'", optopt);
}
+ err_flag = true;
+ break;
default:
- sdlog2_usage("unrecognized flag");
- errx(1, "exiting");
+ warnx("unrecognized flag");
+ err_flag = true;
+ break;
}
}
+ if (err_flag) {
+ sdlog2_usage(NULL);
+ }
+
gps_time = 0;
/* create log root dir */
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret != 0 && errno != EEXIST) {
- err("failed creating log root dir: %s", log_root);
+ err(1, "failed creating log root dir: %s", log_root);
}
/* copy conversion scripts */
@@ -734,8 +763,12 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_status_s buf_status;
+ struct vehicle_gps_position_s buf_gps_pos;
+
memset(&buf_status, 0, sizeof(buf_status));
+ memset(&buf_gps_pos, 0, sizeof(buf_gps_pos));
+
/* warning! using union here to save memory, elements should be used separately! */
union {
struct vehicle_command_s cmd;
@@ -749,7 +782,6 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_local_position_setpoint_s local_pos_sp;
struct vehicle_global_position_s global_pos;
struct position_setpoint_triplet_s triplet;
- struct vehicle_gps_position_s gps_pos;
struct vehicle_vicon_position_s vicon_pos;
struct optical_flow_s flow;
struct rc_channels_s rc;
@@ -763,30 +795,6 @@ int sdlog2_thread_main(int argc, char *argv[])
memset(&buf, 0, sizeof(buf));
- struct {
- int cmd_sub;
- int status_sub;
- int sensor_sub;
- int att_sub;
- int att_sp_sub;
- int rates_sp_sub;
- int act_outputs_sub;
- int act_controls_sub;
- int local_pos_sub;
- int local_pos_sp_sub;
- int global_pos_sub;
- int triplet_sub;
- int gps_pos_sub;
- int vicon_pos_sub;
- int flow_sub;
- int rc_sub;
- int airspeed_sub;
- int esc_sub;
- int global_vel_sp_sub;
- int battery_sub;
- int telemetry_sub;
- } subs;
-
/* log message buffer: header + body */
#pragma pack(push, 1)
struct {
@@ -821,154 +829,51 @@ int sdlog2_thread_main(int argc, char *argv[])
#pragma pack(pop)
memset(&log_msg.body, 0, sizeof(log_msg.body));
- /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
- /* number of messages */
- const ssize_t fdsc = 25;
- /* Sanity check variable and index */
- ssize_t fdsc_count = 0;
- /* file descriptors to wait for */
- struct pollfd fds[fdsc];
+ struct {
+ int cmd_sub;
+ int status_sub;
+ int sensor_sub;
+ int att_sub;
+ int att_sp_sub;
+ int rates_sp_sub;
+ int act_outputs_sub;
+ int act_controls_sub;
+ int local_pos_sub;
+ int local_pos_sp_sub;
+ int global_pos_sub;
+ int triplet_sub;
+ int gps_pos_sub;
+ int vicon_pos_sub;
+ int flow_sub;
+ int rc_sub;
+ int airspeed_sub;
+ int esc_sub;
+ int global_vel_sp_sub;
+ int battery_sub;
+ int telemetry_sub;
+ } subs;
- /* --- VEHICLE COMMAND --- */
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
- fds[fdsc_count].fd = subs.cmd_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- VEHICLE STATUS --- */
subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
- fds[fdsc_count].fd = subs.status_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- GPS POSITION --- */
subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- fds[fdsc_count].fd = subs.gps_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- SENSORS COMBINED --- */
subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- fds[fdsc_count].fd = subs.sensor_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ATTITUDE --- */
subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- fds[fdsc_count].fd = subs.att_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ATTITUDE SETPOINT --- */
subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
- fds[fdsc_count].fd = subs.att_sp_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- RATES SETPOINT --- */
subs.rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
- fds[fdsc_count].fd = subs.rates_sp_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ACTUATOR OUTPUTS --- */
subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS);
- fds[fdsc_count].fd = subs.act_outputs_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ACTUATOR CONTROL --- */
subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
- fds[fdsc_count].fd = subs.act_controls_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- LOCAL POSITION --- */
subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
- fds[fdsc_count].fd = subs.local_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- LOCAL POSITION SETPOINT --- */
subs.local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
- fds[fdsc_count].fd = subs.local_pos_sp_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- GLOBAL POSITION --- */
subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- fds[fdsc_count].fd = subs.global_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- GLOBAL POSITION SETPOINT--- */
subs.triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
- fds[fdsc_count].fd = subs.triplet_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- VICON POSITION --- */
subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
- fds[fdsc_count].fd = subs.vicon_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- OPTICAL FLOW --- */
subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
- fds[fdsc_count].fd = subs.flow_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- RC CHANNELS --- */
subs.rc_sub = orb_subscribe(ORB_ID(rc_channels));
- fds[fdsc_count].fd = subs.rc_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- AIRSPEED --- */
subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
- fds[fdsc_count].fd = subs.airspeed_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ESCs --- */
subs.esc_sub = orb_subscribe(ORB_ID(esc_status));
- fds[fdsc_count].fd = subs.esc_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- GLOBAL VELOCITY SETPOINT --- */
subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
- fds[fdsc_count].fd = subs.global_vel_sp_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- BATTERY --- */
subs.battery_sub = orb_subscribe(ORB_ID(battery_status));
- fds[fdsc_count].fd = subs.battery_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- TELEMETRY STATUS --- */
subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
- fds[fdsc_count].fd = subs.telemetry_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* WARNING: If you get the error message below,
- * then the number of registered messages (fdsc)
- * differs from the number of messages in the above list.
- */
- if (fdsc_count > fdsc) {
- warn("WARNING: Not enough space for poll fds allocated. Check %s:%d", __FILE__, __LINE__);
- fdsc_count = fdsc;
- }
-
- /*
- * set up poll to block for new data,
- * wait for a maximum of 1000 ms
- */
- const int poll_timeout = 1000;
thread_running = true;
@@ -990,8 +895,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (log_on_start) {
/* check GPS topic to get GPS time */
if (log_name_timestamp) {
- if (OK == orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos)) {
- gps_time = buf.gps_pos.time_gps_usec;
+ if (copy_if_updated(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf_gps_pos)) {
+ gps_time = buf_gps_pos.time_gps_usec;
}
}
@@ -999,394 +904,342 @@ int sdlog2_thread_main(int argc, char *argv[])
}
while (!main_thread_should_exit) {
- /* decide use usleep() or blocking poll() */
- bool use_sleep = sleep_delay > 0 && logging_enabled;
+ usleep(sleep_delay);
- /* poll all topics if logging enabled or only management (first 3) if not */
- int poll_ret = poll(fds, logging_enabled ? fdsc_count : 3, use_sleep ? 0 : poll_timeout);
-
- /* handle the poll result */
- if (poll_ret < 0) {
- warnx("ERROR: poll error, stop logging");
- main_thread_should_exit = true;
+ /* --- VEHICLE COMMAND - LOG MANAGEMENT --- */
+ if (copy_if_updated(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd)) {
+ handle_command(&buf.cmd);
+ }
- } else if (poll_ret > 0) {
+ /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
+ bool status_updated = copy_if_updated(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
- /* check all data subscriptions only if logging enabled,
- * logging_enabled can be changed while checking vehicle_command and vehicle_status */
- bool check_data = logging_enabled;
- int ifds = 0;
- int handled_topics = 0;
+ if (status_updated) {
+ if (log_when_armed) {
+ handle_status(&buf_status);
+ }
+ }
- /* --- VEHICLE COMMAND - LOG MANAGEMENT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd);
+ /* --- GPS POSITION - LOG MANAGEMENT --- */
+ bool gps_pos_updated = copy_if_updated(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf_gps_pos);
- handle_command(&buf.cmd);
- handled_topics++;
- }
+ if (gps_pos_updated && log_name_timestamp) {
+ gps_time = buf_gps_pos.time_gps_usec;
+ }
- /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
+ if (!logging_enabled) {
+ continue;
+ }
- if (log_when_armed) {
- handle_status(&buf_status);
- }
+ pthread_mutex_lock(&logbuffer_mutex);
- handled_topics++;
- }
+ /* write time stamp message */
+ log_msg.msg_type = LOG_TIME_MSG;
+ log_msg.body.log_TIME.t = hrt_absolute_time();
+ LOGBUFFER_WRITE_AND_COUNT(TIME);
+
+ /* --- VEHICLE STATUS --- */
+ if (status_updated) {
+ log_msg.msg_type = LOG_STAT_MSG;
+ log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
+ log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
+ log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
+ log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
+ log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
+ LOGBUFFER_WRITE_AND_COUNT(STAT);
+ }
- /* --- GPS POSITION - LOG MANAGEMENT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
+ /* --- GPS POSITION --- */
+ if (gps_pos_updated) {
+ log_msg.msg_type = LOG_GPS_MSG;
+ log_msg.body.log_GPS.gps_time = buf_gps_pos.time_gps_usec;
+ log_msg.body.log_GPS.fix_type = buf_gps_pos.fix_type;
+ log_msg.body.log_GPS.eph = buf_gps_pos.eph_m;
+ log_msg.body.log_GPS.epv = buf_gps_pos.epv_m;
+ log_msg.body.log_GPS.lat = buf_gps_pos.lat;
+ log_msg.body.log_GPS.lon = buf_gps_pos.lon;
+ log_msg.body.log_GPS.alt = buf_gps_pos.alt * 0.001f;
+ log_msg.body.log_GPS.vel_n = buf_gps_pos.vel_n_m_s;
+ log_msg.body.log_GPS.vel_e = buf_gps_pos.vel_e_m_s;
+ log_msg.body.log_GPS.vel_d = buf_gps_pos.vel_d_m_s;
+ log_msg.body.log_GPS.cog = buf_gps_pos.cog_rad;
+ LOGBUFFER_WRITE_AND_COUNT(GPS);
+ }
- if (log_name_timestamp) {
- gps_time = buf.gps_pos.time_gps_usec;
- }
+ /* --- SENSOR COMBINED --- */
+ if (copy_if_updated(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor)) {
+ bool write_IMU = false;
+ bool write_SENS = false;
- handled_topics++;
+ if (buf.sensor.gyro_counter != gyro_counter) {
+ gyro_counter = buf.sensor.gyro_counter;
+ write_IMU = true;
}
- if (!logging_enabled || !check_data || handled_topics >= poll_ret) {
- continue;
+ if (buf.sensor.accelerometer_counter != accelerometer_counter) {
+ accelerometer_counter = buf.sensor.accelerometer_counter;
+ write_IMU = true;
}
- ifds = 1; // begin from VEHICLE STATUS again
-
- pthread_mutex_lock(&logbuffer_mutex);
-
- /* write time stamp message */
- log_msg.msg_type = LOG_TIME_MSG;
- log_msg.body.log_TIME.t = hrt_absolute_time();
- LOGBUFFER_WRITE_AND_COUNT(TIME);
-
- /* --- VEHICLE STATUS --- */
- if (fds[ifds++].revents & POLLIN) {
- /* don't orb_copy, it's already done few lines above */
- log_msg.msg_type = LOG_STAT_MSG;
- log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
- log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
- log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
- log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
- log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
- LOGBUFFER_WRITE_AND_COUNT(STAT);
+ if (buf.sensor.magnetometer_counter != magnetometer_counter) {
+ magnetometer_counter = buf.sensor.magnetometer_counter;
+ write_IMU = true;
}
- /* --- GPS POSITION --- */
- if (fds[ifds++].revents & POLLIN) {
- /* don't orb_copy, it's already done few lines above */
- log_msg.msg_type = LOG_GPS_MSG;
- log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec;
- log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type;
- log_msg.body.log_GPS.eph = buf.gps_pos.eph_m;
- log_msg.body.log_GPS.epv = buf.gps_pos.epv_m;
- log_msg.body.log_GPS.lat = buf.gps_pos.lat;
- log_msg.body.log_GPS.lon = buf.gps_pos.lon;
- log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001f;
- log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s;
- log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s;
- log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s;
- log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad;
- LOGBUFFER_WRITE_AND_COUNT(GPS);
+ if (buf.sensor.baro_counter != baro_counter) {
+ baro_counter = buf.sensor.baro_counter;
+ write_SENS = true;
}
- /* --- SENSOR COMBINED --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor);
- bool write_IMU = false;
- bool write_SENS = false;
-
- if (buf.sensor.gyro_counter != gyro_counter) {
- gyro_counter = buf.sensor.gyro_counter;
- write_IMU = true;
- }
-
- if (buf.sensor.accelerometer_counter != accelerometer_counter) {
- accelerometer_counter = buf.sensor.accelerometer_counter;
- write_IMU = true;
- }
-
- if (buf.sensor.magnetometer_counter != magnetometer_counter) {
- magnetometer_counter = buf.sensor.magnetometer_counter;
- write_IMU = true;
- }
-
- if (buf.sensor.baro_counter != baro_counter) {
- baro_counter = buf.sensor.baro_counter;
- write_SENS = true;
- }
-
- if (buf.sensor.differential_pressure_counter != differential_pressure_counter) {
- differential_pressure_counter = buf.sensor.differential_pressure_counter;
- write_SENS = true;
- }
-
- if (write_IMU) {
- log_msg.msg_type = LOG_IMU_MSG;
- log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0];
- log_msg.body.log_IMU.gyro_y = buf.sensor.gyro_rad_s[1];
- log_msg.body.log_IMU.gyro_z = buf.sensor.gyro_rad_s[2];
- log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer_m_s2[0];
- log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer_m_s2[1];
- log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer_m_s2[2];
- log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0];
- log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1];
- log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2];
- LOGBUFFER_WRITE_AND_COUNT(IMU);
- }
-
- if (write_SENS) {
- log_msg.msg_type = LOG_SENS_MSG;
- log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar;
- log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter;
- log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius;
- log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa;
- LOGBUFFER_WRITE_AND_COUNT(SENS);
- }
+ if (buf.sensor.differential_pressure_counter != differential_pressure_counter) {
+ differential_pressure_counter = buf.sensor.differential_pressure_counter;
+ write_SENS = true;
}
- /* --- ATTITUDE --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att);
- log_msg.msg_type = LOG_ATT_MSG;
- log_msg.body.log_ATT.roll = buf.att.roll;
- log_msg.body.log_ATT.pitch = buf.att.pitch;
- log_msg.body.log_ATT.yaw = buf.att.yaw;
- log_msg.body.log_ATT.roll_rate = buf.att.rollspeed;
- log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed;
- log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed;
- log_msg.body.log_ATT.gx = buf.att.g_comp[0];
- log_msg.body.log_ATT.gy = buf.att.g_comp[1];
- log_msg.body.log_ATT.gz = buf.att.g_comp[2];
- LOGBUFFER_WRITE_AND_COUNT(ATT);
+ if (write_IMU) {
+ log_msg.msg_type = LOG_IMU_MSG;
+ log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0];
+ log_msg.body.log_IMU.gyro_y = buf.sensor.gyro_rad_s[1];
+ log_msg.body.log_IMU.gyro_z = buf.sensor.gyro_rad_s[2];
+ log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer_m_s2[0];
+ log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer_m_s2[1];
+ log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer_m_s2[2];
+ log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0];
+ log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1];
+ log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2];
+ LOGBUFFER_WRITE_AND_COUNT(IMU);
}
- /* --- ATTITUDE SETPOINT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp);
- log_msg.msg_type = LOG_ATSP_MSG;
- log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body;
- log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body;
- log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body;
- log_msg.body.log_ATSP.thrust_sp = buf.att_sp.thrust;
- LOGBUFFER_WRITE_AND_COUNT(ATSP);
+ if (write_SENS) {
+ log_msg.msg_type = LOG_SENS_MSG;
+ log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar;
+ log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter;
+ log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius;
+ log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa;
+ LOGBUFFER_WRITE_AND_COUNT(SENS);
}
+ }
- /* --- RATES SETPOINT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_rates_setpoint), subs.rates_sp_sub, &buf.rates_sp);
- log_msg.msg_type = LOG_ARSP_MSG;
- log_msg.body.log_ARSP.roll_rate_sp = buf.rates_sp.roll;
- log_msg.body.log_ARSP.pitch_rate_sp = buf.rates_sp.pitch;
- log_msg.body.log_ARSP.yaw_rate_sp = buf.rates_sp.yaw;
- LOGBUFFER_WRITE_AND_COUNT(ARSP);
- }
+ /* --- ATTITUDE --- */
+ if (copy_if_updated(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att)) {
+ log_msg.msg_type = LOG_ATT_MSG;
+ log_msg.body.log_ATT.roll = buf.att.roll;
+ log_msg.body.log_ATT.pitch = buf.att.pitch;
+ log_msg.body.log_ATT.yaw = buf.att.yaw;
+ log_msg.body.log_ATT.roll_rate = buf.att.rollspeed;
+ log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed;
+ log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed;
+ log_msg.body.log_ATT.gx = buf.att.g_comp[0];
+ log_msg.body.log_ATT.gy = buf.att.g_comp[1];
+ log_msg.body.log_ATT.gz = buf.att.g_comp[2];
+ LOGBUFFER_WRITE_AND_COUNT(ATT);
+ }
- /* --- ACTUATOR OUTPUTS --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs);
- log_msg.msg_type = LOG_OUT0_MSG;
- memcpy(log_msg.body.log_OUT0.output, buf.act_outputs.output, sizeof(log_msg.body.log_OUT0.output));
- LOGBUFFER_WRITE_AND_COUNT(OUT0);
- }
+ /* --- ATTITUDE SETPOINT --- */
+ if (copy_if_updated(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp)) {
+ log_msg.msg_type = LOG_ATSP_MSG;
+ log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body;
+ log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body;
+ log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body;
+ log_msg.body.log_ATSP.thrust_sp = buf.att_sp.thrust;
+ LOGBUFFER_WRITE_AND_COUNT(ATSP);
+ }
- /* --- ACTUATOR CONTROL --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls);
- log_msg.msg_type = LOG_ATTC_MSG;
- log_msg.body.log_ATTC.roll = buf.act_controls.control[0];
- log_msg.body.log_ATTC.pitch = buf.act_controls.control[1];
- log_msg.body.log_ATTC.yaw = buf.act_controls.control[2];
- log_msg.body.log_ATTC.thrust = buf.act_controls.control[3];
- LOGBUFFER_WRITE_AND_COUNT(ATTC);
- }
+ /* --- RATES SETPOINT --- */
+ if (copy_if_updated(ORB_ID(vehicle_rates_setpoint), subs.rates_sp_sub, &buf.rates_sp)) {
+ log_msg.msg_type = LOG_ARSP_MSG;
+ log_msg.body.log_ARSP.roll_rate_sp = buf.rates_sp.roll;
+ log_msg.body.log_ARSP.pitch_rate_sp = buf.rates_sp.pitch;
+ log_msg.body.log_ARSP.yaw_rate_sp = buf.rates_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(ARSP);
+ }
- /* --- LOCAL POSITION --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos);
- log_msg.msg_type = LOG_LPOS_MSG;
- log_msg.body.log_LPOS.x = buf.local_pos.x;
- log_msg.body.log_LPOS.y = buf.local_pos.y;
- log_msg.body.log_LPOS.z = buf.local_pos.z;
- log_msg.body.log_LPOS.vx = buf.local_pos.vx;
- log_msg.body.log_LPOS.vy = buf.local_pos.vy;
- log_msg.body.log_LPOS.vz = buf.local_pos.vz;
- log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat;
- log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon;
- log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
- log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
- log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
- log_msg.body.log_LPOS.landed = buf.local_pos.landed;
- LOGBUFFER_WRITE_AND_COUNT(LPOS);
-
- if (buf.local_pos.dist_bottom_valid) {
- dist_bottom_present = true;
- }
- if (dist_bottom_present) {
- log_msg.msg_type = LOG_DIST_MSG;
- log_msg.body.log_DIST.bottom = buf.local_pos.dist_bottom;
- log_msg.body.log_DIST.bottom_rate = buf.local_pos.dist_bottom_rate;
- log_msg.body.log_DIST.flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
- LOGBUFFER_WRITE_AND_COUNT(DIST);
- }
- }
+ /* --- ACTUATOR OUTPUTS --- */
+ if (copy_if_updated(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs)) {
+ log_msg.msg_type = LOG_OUT0_MSG;
+ memcpy(log_msg.body.log_OUT0.output, buf.act_outputs.output, sizeof(log_msg.body.log_OUT0.output));
+ LOGBUFFER_WRITE_AND_COUNT(OUT0);
+ }
- /* --- LOCAL POSITION SETPOINT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp);
- log_msg.msg_type = LOG_LPSP_MSG;
- log_msg.body.log_LPSP.x = buf.local_pos_sp.x;
- log_msg.body.log_LPSP.y = buf.local_pos_sp.y;
- log_msg.body.log_LPSP.z = buf.local_pos_sp.z;
- log_msg.body.log_LPSP.yaw = buf.local_pos_sp.yaw;
- LOGBUFFER_WRITE_AND_COUNT(LPSP);
- }
+ /* --- ACTUATOR CONTROL --- */
+ if (copy_if_updated(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls)) {
+ log_msg.msg_type = LOG_ATTC_MSG;
+ log_msg.body.log_ATTC.roll = buf.act_controls.control[0];
+ log_msg.body.log_ATTC.pitch = buf.act_controls.control[1];
+ log_msg.body.log_ATTC.yaw = buf.act_controls.control[2];
+ log_msg.body.log_ATTC.thrust = buf.act_controls.control[3];
+ LOGBUFFER_WRITE_AND_COUNT(ATTC);
+ }
- /* --- GLOBAL POSITION --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos);
- log_msg.msg_type = LOG_GPOS_MSG;
- log_msg.body.log_GPOS.lat = buf.global_pos.lat * 1e7;
- log_msg.body.log_GPOS.lon = buf.global_pos.lon * 1e7;
- log_msg.body.log_GPOS.alt = buf.global_pos.alt;
- log_msg.body.log_GPOS.vel_n = buf.global_pos.vel_n;
- log_msg.body.log_GPOS.vel_e = buf.global_pos.vel_e;
- log_msg.body.log_GPOS.vel_d = buf.global_pos.vel_d;
- log_msg.body.log_GPOS.baro_alt = buf.global_pos.baro_alt;
- log_msg.body.log_GPOS.flags = (buf.global_pos.baro_valid ? 1 : 0) | (buf.global_pos.global_valid ? 2 : 0);
- LOGBUFFER_WRITE_AND_COUNT(GPOS);
+ /* --- LOCAL POSITION --- */
+ if (copy_if_updated(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos)) {
+ log_msg.msg_type = LOG_LPOS_MSG;
+ log_msg.body.log_LPOS.x = buf.local_pos.x;
+ log_msg.body.log_LPOS.y = buf.local_pos.y;
+ log_msg.body.log_LPOS.z = buf.local_pos.z;
+ log_msg.body.log_LPOS.vx = buf.local_pos.vx;
+ log_msg.body.log_LPOS.vy = buf.local_pos.vy;
+ log_msg.body.log_LPOS.vz = buf.local_pos.vz;
+ log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat;
+ log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon;
+ log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
+ log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
+ log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
+ log_msg.body.log_LPOS.landed = buf.local_pos.landed;
+ LOGBUFFER_WRITE_AND_COUNT(LPOS);
+
+ if (buf.local_pos.dist_bottom_valid) {
+ dist_bottom_present = true;
}
- /* --- GLOBAL POSITION SETPOINT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(position_setpoint_triplet), subs.triplet_sub, &buf.triplet);
- log_msg.msg_type = LOG_GPSP_MSG;
- log_msg.body.log_GPSP.nav_state = buf.triplet.nav_state;
- log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d);
- log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d);
- log_msg.body.log_GPSP.alt = buf.triplet.current.alt;
- log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw;
- log_msg.body.log_GPSP.type = buf.triplet.current.type;
- log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius;
- log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction;
- log_msg.body.log_GPSP.pitch_min = buf.triplet.current.pitch_min;
- LOGBUFFER_WRITE_AND_COUNT(GPSP);
+ if (dist_bottom_present) {
+ log_msg.msg_type = LOG_DIST_MSG;
+ log_msg.body.log_DIST.bottom = buf.local_pos.dist_bottom;
+ log_msg.body.log_DIST.bottom_rate = buf.local_pos.dist_bottom_rate;
+ log_msg.body.log_DIST.flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
+ LOGBUFFER_WRITE_AND_COUNT(DIST);
}
+ }
- /* --- VICON POSITION --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos);
- // TODO not implemented yet
- }
+ /* --- LOCAL POSITION SETPOINT --- */
+ if (copy_if_updated(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp)) {
+ log_msg.msg_type = LOG_LPSP_MSG;
+ log_msg.body.log_LPSP.x = buf.local_pos_sp.x;
+ log_msg.body.log_LPSP.y = buf.local_pos_sp.y;
+ log_msg.body.log_LPSP.z = buf.local_pos_sp.z;
+ log_msg.body.log_LPSP.yaw = buf.local_pos_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(LPSP);
+ }
- /* --- FLOW --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow);
- log_msg.msg_type = LOG_FLOW_MSG;
- log_msg.body.log_FLOW.flow_raw_x = buf.flow.flow_raw_x;
- log_msg.body.log_FLOW.flow_raw_y = buf.flow.flow_raw_y;
- log_msg.body.log_FLOW.flow_comp_x = buf.flow.flow_comp_x_m;
- log_msg.body.log_FLOW.flow_comp_y = buf.flow.flow_comp_y_m;
- log_msg.body.log_FLOW.distance = buf.flow.ground_distance_m;
- log_msg.body.log_FLOW.quality = buf.flow.quality;
- log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
- LOGBUFFER_WRITE_AND_COUNT(FLOW);
- }
+ /* --- GLOBAL POSITION --- */
+ if (copy_if_updated(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos)) {
+ log_msg.msg_type = LOG_GPOS_MSG;
+ log_msg.body.log_GPOS.lat = buf.global_pos.lat * 1e7;
+ log_msg.body.log_GPOS.lon = buf.global_pos.lon * 1e7;
+ log_msg.body.log_GPOS.alt = buf.global_pos.alt;
+ log_msg.body.log_GPOS.vel_n = buf.global_pos.vel_n;
+ log_msg.body.log_GPOS.vel_e = buf.global_pos.vel_e;
+ log_msg.body.log_GPOS.vel_d = buf.global_pos.vel_d;
+ log_msg.body.log_GPOS.baro_alt = buf.global_pos.baro_alt;
+ log_msg.body.log_GPOS.flags = (buf.global_pos.baro_valid ? 1 : 0) | (buf.global_pos.global_valid ? 2 : 0);
+ LOGBUFFER_WRITE_AND_COUNT(GPOS);
+ }
- /* --- RC CHANNELS --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(rc_channels), subs.rc_sub, &buf.rc);
- log_msg.msg_type = LOG_RC_MSG;
- /* Copy only the first 8 channels of 14 */
- memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel));
- log_msg.body.log_RC.channel_count = buf.rc.chan_count;
- LOGBUFFER_WRITE_AND_COUNT(RC);
- }
+ /* --- GLOBAL POSITION SETPOINT --- */
+ if (copy_if_updated(ORB_ID(position_setpoint_triplet), subs.triplet_sub, &buf.triplet)) {
+ log_msg.msg_type = LOG_GPSP_MSG;
+ log_msg.body.log_GPSP.nav_state = buf.triplet.nav_state;
+ log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d);
+ log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d);
+ log_msg.body.log_GPSP.alt = buf.triplet.current.alt;
+ log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw;
+ log_msg.body.log_GPSP.type = buf.triplet.current.type;
+ log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius;
+ log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction;
+ log_msg.body.log_GPSP.pitch_min = buf.triplet.current.pitch_min;
+ LOGBUFFER_WRITE_AND_COUNT(GPSP);
+ }
- /* --- AIRSPEED --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed);
- log_msg.msg_type = LOG_AIRS_MSG;
- log_msg.body.log_AIRS.indicated_airspeed = buf.airspeed.indicated_airspeed_m_s;
- log_msg.body.log_AIRS.true_airspeed = buf.airspeed.true_airspeed_m_s;
- LOGBUFFER_WRITE_AND_COUNT(AIRS);
- }
+ /* --- VICON POSITION --- */
+ if (copy_if_updated(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos)) {
+ // TODO not implemented yet
+ }
- /* --- ESCs --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(esc_status), subs.esc_sub, &buf.esc);
-
- for (uint8_t i = 0; i < buf.esc.esc_count; i++) {
- log_msg.msg_type = LOG_ESC_MSG;
- log_msg.body.log_ESC.counter = buf.esc.counter;
- log_msg.body.log_ESC.esc_count = buf.esc.esc_count;
- log_msg.body.log_ESC.esc_connectiontype = buf.esc.esc_connectiontype;
- log_msg.body.log_ESC.esc_num = i;
- log_msg.body.log_ESC.esc_address = buf.esc.esc[i].esc_address;
- log_msg.body.log_ESC.esc_version = buf.esc.esc[i].esc_version;
- log_msg.body.log_ESC.esc_voltage = buf.esc.esc[i].esc_voltage;
- log_msg.body.log_ESC.esc_current = buf.esc.esc[i].esc_current;
- log_msg.body.log_ESC.esc_rpm = buf.esc.esc[i].esc_rpm;
- log_msg.body.log_ESC.esc_temperature = buf.esc.esc[i].esc_temperature;
- log_msg.body.log_ESC.esc_setpoint = buf.esc.esc[i].esc_setpoint;
- log_msg.body.log_ESC.esc_setpoint_raw = buf.esc.esc[i].esc_setpoint_raw;
- LOGBUFFER_WRITE_AND_COUNT(ESC);
- }
- }
+ /* --- FLOW --- */
+ if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
+ log_msg.msg_type = LOG_FLOW_MSG;
+ log_msg.body.log_FLOW.flow_raw_x = buf.flow.flow_raw_x;
+ log_msg.body.log_FLOW.flow_raw_y = buf.flow.flow_raw_y;
+ log_msg.body.log_FLOW.flow_comp_x = buf.flow.flow_comp_x_m;
+ log_msg.body.log_FLOW.flow_comp_y = buf.flow.flow_comp_y_m;
+ log_msg.body.log_FLOW.distance = buf.flow.ground_distance_m;
+ log_msg.body.log_FLOW.quality = buf.flow.quality;
+ log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
+ LOGBUFFER_WRITE_AND_COUNT(FLOW);
+ }
- /* --- GLOBAL VELOCITY SETPOINT --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_global_velocity_setpoint), subs.global_vel_sp_sub, &buf.global_vel_sp);
- log_msg.msg_type = LOG_GVSP_MSG;
- log_msg.body.log_GVSP.vx = buf.global_vel_sp.vx;
- log_msg.body.log_GVSP.vy = buf.global_vel_sp.vy;
- log_msg.body.log_GVSP.vz = buf.global_vel_sp.vz;
- LOGBUFFER_WRITE_AND_COUNT(GVSP);
- }
+ /* --- RC CHANNELS --- */
+ if (copy_if_updated(ORB_ID(rc_channels), subs.rc_sub, &buf.rc)) {
+ log_msg.msg_type = LOG_RC_MSG;
+ /* Copy only the first 8 channels of 14 */
+ memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel));
+ log_msg.body.log_RC.channel_count = buf.rc.chan_count;
+ LOGBUFFER_WRITE_AND_COUNT(RC);
+ }
- /* --- BATTERY --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(battery_status), subs.battery_sub, &buf.battery);
- log_msg.msg_type = LOG_BATT_MSG;
- log_msg.body.log_BATT.voltage = buf.battery.voltage_v;
- log_msg.body.log_BATT.voltage_filtered = buf.battery.voltage_filtered_v;
- log_msg.body.log_BATT.current = buf.battery.current_a;
- log_msg.body.log_BATT.discharged = buf.battery.discharged_mah;
- LOGBUFFER_WRITE_AND_COUNT(BATT);
- }
+ /* --- AIRSPEED --- */
+ if (copy_if_updated(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed)) {
+ log_msg.msg_type = LOG_AIRS_MSG;
+ log_msg.body.log_AIRS.indicated_airspeed = buf.airspeed.indicated_airspeed_m_s;
+ log_msg.body.log_AIRS.true_airspeed = buf.airspeed.true_airspeed_m_s;
+ LOGBUFFER_WRITE_AND_COUNT(AIRS);
+ }
- /* --- TELEMETRY --- */
- if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry);
- log_msg.msg_type = LOG_TELE_MSG;
- log_msg.body.log_TELE.rssi = buf.telemetry.rssi;
- log_msg.body.log_TELE.remote_rssi = buf.telemetry.remote_rssi;
- log_msg.body.log_TELE.noise = buf.telemetry.noise;
- log_msg.body.log_TELE.remote_noise = buf.telemetry.remote_noise;
- log_msg.body.log_TELE.rxerrors = buf.telemetry.rxerrors;
- log_msg.body.log_TELE.fixed = buf.telemetry.fixed;
- log_msg.body.log_TELE.txbuf = buf.telemetry.txbuf;
- LOGBUFFER_WRITE_AND_COUNT(TELE);
+ /* --- ESCs --- */
+ if (copy_if_updated(ORB_ID(esc_status), subs.esc_sub, &buf.esc)) {
+ for (uint8_t i = 0; i < buf.esc.esc_count; i++) {
+ log_msg.msg_type = LOG_ESC_MSG;
+ log_msg.body.log_ESC.counter = buf.esc.counter;
+ log_msg.body.log_ESC.esc_count = buf.esc.esc_count;
+ log_msg.body.log_ESC.esc_connectiontype = buf.esc.esc_connectiontype;
+ log_msg.body.log_ESC.esc_num = i;
+ log_msg.body.log_ESC.esc_address = buf.esc.esc[i].esc_address;
+ log_msg.body.log_ESC.esc_version = buf.esc.esc[i].esc_version;
+ log_msg.body.log_ESC.esc_voltage = buf.esc.esc[i].esc_voltage;
+ log_msg.body.log_ESC.esc_current = buf.esc.esc[i].esc_current;
+ log_msg.body.log_ESC.esc_rpm = buf.esc.esc[i].esc_rpm;
+ log_msg.body.log_ESC.esc_temperature = buf.esc.esc[i].esc_temperature;
+ log_msg.body.log_ESC.esc_setpoint = buf.esc.esc[i].esc_setpoint;
+ log_msg.body.log_ESC.esc_setpoint_raw = buf.esc.esc[i].esc_setpoint_raw;
+ LOGBUFFER_WRITE_AND_COUNT(ESC);
}
+ }
- /* signal the other thread new data, but not yet unlock */
- if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
- /* only request write if several packets can be written at once */
- pthread_cond_signal(&logbuffer_cond);
- }
+ /* --- GLOBAL VELOCITY SETPOINT --- */
+ if (copy_if_updated(ORB_ID(vehicle_global_velocity_setpoint), subs.global_vel_sp_sub, &buf.global_vel_sp)) {
+ log_msg.msg_type = LOG_GVSP_MSG;
+ log_msg.body.log_GVSP.vx = buf.global_vel_sp.vx;
+ log_msg.body.log_GVSP.vy = buf.global_vel_sp.vy;
+ log_msg.body.log_GVSP.vz = buf.global_vel_sp.vz;
+ LOGBUFFER_WRITE_AND_COUNT(GVSP);
+ }
- /* unlock, now the writer thread may run */
- pthread_mutex_unlock(&logbuffer_mutex);
+ /* --- BATTERY --- */
+ if (copy_if_updated(ORB_ID(battery_status), subs.battery_sub, &buf.battery)) {
+ log_msg.msg_type = LOG_BATT_MSG;
+ log_msg.body.log_BATT.voltage = buf.battery.voltage_v;
+ log_msg.body.log_BATT.voltage_filtered = buf.battery.voltage_filtered_v;
+ log_msg.body.log_BATT.current = buf.battery.current_a;
+ log_msg.body.log_BATT.discharged = buf.battery.discharged_mah;
+ LOGBUFFER_WRITE_AND_COUNT(BATT);
}
- if (use_sleep) {
- usleep(sleep_delay);
+ /* --- TELEMETRY --- */
+ if (copy_if_updated(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry)) {
+ log_msg.msg_type = LOG_TELE_MSG;
+ log_msg.body.log_TELE.rssi = buf.telemetry.rssi;
+ log_msg.body.log_TELE.remote_rssi = buf.telemetry.remote_rssi;
+ log_msg.body.log_TELE.noise = buf.telemetry.noise;
+ log_msg.body.log_TELE.remote_noise = buf.telemetry.remote_noise;
+ log_msg.body.log_TELE.rxerrors = buf.telemetry.rxerrors;
+ log_msg.body.log_TELE.fixed = buf.telemetry.fixed;
+ log_msg.body.log_TELE.txbuf = buf.telemetry.txbuf;
+ LOGBUFFER_WRITE_AND_COUNT(TELE);
}
+
+ /* signal the other thread new data, but not yet unlock */
+ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
+ /* only request write if several packets can be written at once */
+ pthread_cond_signal(&logbuffer_cond);
+ }
+
+ /* unlock, now the writer thread may run */
+ pthread_mutex_unlock(&logbuffer_mutex);
}
- if (logging_enabled)
+ if (logging_enabled) {
sdlog2_stop_log();
+ }
pthread_mutex_destroy(&logbuffer_mutex);
pthread_cond_destroy(&logbuffer_cond);
@@ -1461,8 +1314,6 @@ int file_copy(const char *file_old, const char *file_new)
void handle_command(struct vehicle_command_s *cmd)
{
- /* result of the command */
- uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
int param;
/* request to set different system mode */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 16bfc355d..e27518aa0 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -267,13 +267,13 @@ struct log_DIST_s {
/* --- TELE - TELEMETRY STATUS --- */
#define LOG_TELE_MSG 22
struct log_TELE_s {
- uint8_t rssi;
- uint8_t remote_rssi;
- uint8_t noise;
- uint8_t remote_noise;
- uint16_t rxerrors;
- uint16_t fixed;
- uint8_t txbuf;
+ uint8_t rssi;
+ uint8_t remote_rssi;
+ uint8_t noise;
+ uint8_t remote_noise;
+ uint16_t rxerrors;
+ uint16_t fixed;
+ uint8_t txbuf;
};
/********** SYSTEM MESSAGES, ID > 0x80 **********/
diff --git a/src/systemcmds/dumpfile/dumpfile.c b/src/systemcmds/dumpfile/dumpfile.c
new file mode 100644
index 000000000..c18814342
--- /dev/null
+++ b/src/systemcmds/dumpfile/dumpfile.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file dumpfile.c
+ *
+ * Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+#include <fcntl.h>
+#include <termios.h>
+
+#include <systemlib/err.h>
+
+__EXPORT int dumpfile_main(int argc, char *argv[]);
+
+int
+dumpfile_main(int argc, char *argv[])
+{
+ if (argc < 2) {
+ errx(1, "usage: dumpfile <filename>");
+ }
+
+ /* open input file */
+ FILE *f;
+ f = fopen(argv[1], "r");
+
+ if (f == NULL) {
+ printf("ERROR\n");
+ exit(1);
+ }
+
+ /* get file size */
+ fseek(f, 0L, SEEK_END);
+ int size = ftell(f);
+ fseek(f, 0L, SEEK_SET);
+
+ printf("OK %d\n", size);
+
+ /* configure stdout */
+ int out = fileno(stdout);
+
+ struct termios tc;
+ struct termios tc_old;
+ tcgetattr(out, &tc);
+
+ /* save old terminal attributes to restore it later on exit */
+ memcpy(&tc_old, &tc, sizeof(tc));
+
+ /* don't add CR on each LF*/
+ tc.c_oflag &= ~ONLCR;
+
+ if (tcsetattr(out, TCSANOW, &tc) < 0) {
+ warnx("ERROR setting stdout attributes");
+ exit(1);
+ }
+
+ char buf[512];
+ int nread;
+
+ /* dump file */
+ while ((nread = fread(buf, 1, sizeof(buf), f)) > 0) {
+ if (write(out, buf, nread) <= 0) {
+ warnx("error dumping file");
+ break;
+ }
+ }
+
+ fsync(out);
+ fclose(f);
+
+ /* restore old terminal attributes */
+ if (tcsetattr(out, TCSANOW, &tc_old) < 0) {
+ warnx("ERROR restoring stdout attributes");
+ exit(1);
+ }
+
+ return OK;
+}
diff --git a/src/systemcmds/dumpfile/module.mk b/src/systemcmds/dumpfile/module.mk
new file mode 100644
index 000000000..36461f477
--- /dev/null
+++ b/src/systemcmds/dumpfile/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Dump file utility
+#
+
+MODULE_COMMAND = dumpfile
+SRCS = dumpfile.c
+
+MAXOPTIMIZATION = -Os