Skip to content

Commit

Permalink
Merge branch 'master' of github.com:PX4/Firmware into gpio_led_fmuv2
Browse files Browse the repository at this point in the history
  • Loading branch information
LorenzMeier committed Mar 12, 2014
2 parents 7749ed1 + db04e00 commit caef8d1
Show file tree
Hide file tree
Showing 24 changed files with 868 additions and 585 deletions.
133 changes: 133 additions & 0 deletions Tools/fetch_log.py
Original file line number Diff line number Diff line change
@@ -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()
83 changes: 83 additions & 0 deletions Tools/px_romfs_pruner.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
#!/usr/bin/env python
############################################################################
#
# Copyright (C) 2014 PX4 Development Team. All rights reserved.
# Author: Julian Oes <[email protected]>

# 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()
1 change: 1 addition & 0 deletions makefiles/config_px4fmu-v1_default.mk
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/hw_ver
MODULES += systemcmds/dumpfile

#
# General system control
Expand Down
1 change: 1 addition & 0 deletions makefiles/config_px4fmu-v2_default.mk
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/mtd
MODULES += systemcmds/hw_ver
MODULES += systemcmds/dumpfile

#
# General system control
Expand Down
4 changes: 4 additions & 0 deletions makefiles/firmware.mk
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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)

Expand Down
6 changes: 3 additions & 3 deletions nuttx-configs/px4fmu-v1/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down
17 changes: 9 additions & 8 deletions src/lib/launchdetection/CatapultLaunchMethod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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")
{

}
Expand Down Expand Up @@ -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;
}

}
11 changes: 8 additions & 3 deletions src/lib/launchdetection/CatapultLaunchMethod.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -68,3 +71,5 @@ class CatapultLaunchMethod : public LaunchMethod
};

#endif /* CATAPULTLAUNCHMETHOD_H_ */

}
18 changes: 7 additions & 11 deletions src/lib/launchdetection/LaunchDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down Expand Up @@ -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();
}
}
Loading

0 comments on commit caef8d1

Please sign in to comment.