Merge branch 'master' of github.com:PX4/Firmware into vector_control

This commit is contained in:
Lorenz Meier
2013-08-19 09:05:16 +02:00
114 changed files with 10309 additions and 1416 deletions
+4 -1
View File
@@ -24,4 +24,7 @@ Firmware.sublime-workspace
Images/*.bin
Images/*.px4
mavlink/include/mavlink/v0.9/
NuttX
/NuttX
/Documentation/doxy.log
/Documentation/html/
/Documentation/doxygen*objdb*tmp
+298
View File
@@ -0,0 +1,298 @@
# GDB/Python functions for dealing with NuttX
import gdb, gdb.types
class NX_task(object):
"""Reference to a NuttX task and methods for introspecting it"""
def __init__(self, tcb_ptr):
self._tcb = tcb_ptr.dereference()
self._group = self._tcb['group'].dereference()
self.pid = tcb_ptr['pid']
@classmethod
def for_tcb(cls, tcb):
"""return a task with the given TCB pointer"""
pidhash_sym = gdb.lookup_global_symbol('g_pidhash')
pidhash_value = pidhash_sym.value()
pidhash_type = pidhash_sym.type
for i in range(pidhash_type.range()[0],pidhash_type.range()[1]):
pidhash_entry = pidhash_value[i]
if pidhash_entry['tcb'] == tcb:
return cls(pidhash_entry['tcb'])
return None
@classmethod
def for_pid(cls, pid):
"""return a task for the given PID"""
pidhash_sym = gdb.lookup_global_symbol('g_pidhash')
pidhash_value = pidhash_sym.value()
pidhash_type = pidhash_sym.type
for i in range(pidhash_type.range()[0],pidhash_type.range()[1]):
pidhash_entry = pidhash_value[i]
if pidhash_entry['pid'] == pid:
return cls(pidhash_entry['tcb'])
return None
@staticmethod
def pids():
"""return a list of all PIDs"""
pidhash_sym = gdb.lookup_global_symbol('g_pidhash')
pidhash_value = pidhash_sym.value()
pidhash_type = pidhash_sym.type
result = []
for i in range(pidhash_type.range()[0],pidhash_type.range()[1]):
entry = pidhash_value[i]
pid = int(entry['pid'])
if pid is not -1:
result.append(pid)
return result
@staticmethod
def tasks():
"""return a list of all tasks"""
tasks = []
for pid in NX_task.pids():
tasks.append(NX_task.for_pid(pid))
return tasks
def _state_is(self, state):
"""tests the current state of the task against the passed-in state name"""
statenames = gdb.types.make_enum_dict(gdb.lookup_type('enum tstate_e'))
if self._tcb['task_state'] == statenames[state]:
return True
return False
@property
def stack_used(self):
"""calculate the stack used by the thread"""
if 'stack_used' not in self.__dict__:
stack_base = self._tcb['stack_alloc_ptr'].cast(gdb.lookup_type('unsigned char').pointer())
if stack_base == 0:
self.__dict__['stack_used'] = 0
else:
stack_limit = self._tcb['adj_stack_size']
for offset in range(0, stack_limit):
if stack_base[offset] != 0xff:
break
self.__dict__['stack_used'] = stack_limit - offset
return self.__dict__['stack_used']
@property
def name(self):
"""return the task's name"""
return self._tcb['name'].string()
@property
def state(self):
"""return the name of the task's current state"""
statenames = gdb.types.make_enum_dict(gdb.lookup_type('enum tstate_e'))
for name,value in statenames.iteritems():
if value == self._tcb['task_state']:
return name
return 'UNKNOWN'
@property
def waiting_for(self):
"""return a description of what the task is waiting for, if it is waiting"""
if self._state_is('TSTATE_WAIT_SEM'):
waitsem = self._tcb['waitsem'].dereference()
waitsem_holder = waitsem['holder']
holder = NX_task.for_tcb(waitsem_holder['htcb'])
if holder is not None:
return '{}({})'.format(waitsem.address, holder.name)
else:
return '{}(<bad holder>)'.format(waitsem.address)
if self._state_is('TSTATE_WAIT_SIG'):
return 'signal'
return None
@property
def is_waiting(self):
"""tests whether the task is waiting for something"""
if self._state_is('TSTATE_WAIT_SEM') or self._state_is('TSTATE_WAIT_SIG'):
return True
@property
def is_runnable(self):
"""tests whether the task is runnable"""
if (self._state_is('TSTATE_TASK_PENDING') or
self._state_is('TSTATE_TASK_READYTORUN') or
self._state_is('TSTATE_TASK_RUNNING')):
return True
return False
@property
def file_descriptors(self):
"""return a dictionary of file descriptors and inode pointers"""
filelist = self._group['tg_filelist']
filearray = filelist['fl_files']
result = dict()
for i in range(filearray.type.range()[0],filearray.type.range()[1]):
inode = long(filearray[i]['f_inode'])
if inode != 0:
result[i] = inode
return result
@property
def registers(self):
if 'registers' not in self.__dict__:
registers = dict()
if self._state_is('TSTATE_TASK_RUNNING'):
# XXX need to fix this to handle interrupt context
registers['R0'] = long(gdb.parse_and_eval('$r0'))
registers['R1'] = long(gdb.parse_and_eval('$r1'))
registers['R2'] = long(gdb.parse_and_eval('$r2'))
registers['R3'] = long(gdb.parse_and_eval('$r3'))
registers['R4'] = long(gdb.parse_and_eval('$r4'))
registers['R5'] = long(gdb.parse_and_eval('$r5'))
registers['R6'] = long(gdb.parse_and_eval('$r6'))
registers['R7'] = long(gdb.parse_and_eval('$r7'))
registers['R8'] = long(gdb.parse_and_eval('$r8'))
registers['R9'] = long(gdb.parse_and_eval('$r9'))
registers['R10'] = long(gdb.parse_and_eval('$r10'))
registers['R11'] = long(gdb.parse_and_eval('$r11'))
registers['R12'] = long(gdb.parse_and_eval('$r12'))
registers['R13'] = long(gdb.parse_and_eval('$r13'))
registers['SP'] = long(gdb.parse_and_eval('$sp'))
registers['R14'] = long(gdb.parse_and_eval('$r14'))
registers['LR'] = long(gdb.parse_and_eval('$lr'))
registers['R15'] = long(gdb.parse_and_eval('$r15'))
registers['PC'] = long(gdb.parse_and_eval('$pc'))
registers['XPSR'] = long(gdb.parse_and_eval('$xpsr'))
# this would only be valid if we were in an interrupt
registers['EXC_RETURN'] = 0
# we should be able to get this...
registers['PRIMASK'] = 0
else:
context = self._tcb['xcp']
regs = context['regs']
registers['R0'] = long(regs[27])
registers['R1'] = long(regs[28])
registers['R2'] = long(regs[29])
registers['R3'] = long(regs[30])
registers['R4'] = long(regs[2])
registers['R5'] = long(regs[3])
registers['R6'] = long(regs[4])
registers['R7'] = long(regs[5])
registers['R8'] = long(regs[6])
registers['R9'] = long(regs[7])
registers['R10'] = long(regs[8])
registers['R11'] = long(regs[9])
registers['R12'] = long(regs[31])
registers['R13'] = long(regs[0])
registers['SP'] = long(regs[0])
registers['R14'] = long(regs[32])
registers['LR'] = long(regs[32])
registers['R15'] = long(regs[33])
registers['PC'] = long(regs[33])
registers['XPSR'] = long(regs[34])
registers['EXC_RETURN'] = long(regs[10])
registers['PRIMASK'] = long(regs[1])
self.__dict__['registers'] = registers
return self.__dict__['registers']
def __repr__(self):
return "<NX_task {}>".format(self.pid)
def __str__(self):
return "{}:{}".format(self.pid, self.name)
def __format__(self, format_spec):
return format_spec.format(
pid = self.pid,
name = self.name,
state = self.state,
waiting_for = self.waiting_for,
stack_used = self.stack_used,
stack_limit = self._tcb['adj_stack_size'],
file_descriptors = self.file_descriptors,
registers = self.registers
)
class NX_show_task (gdb.Command):
"""(NuttX) prints information about a task"""
def __init__(self):
super(NX_show_task, self).__init__("show task", gdb.COMMAND_USER)
def invoke(self, arg, from_tty):
t = NX_task.for_pid(int(arg))
if t is not None:
my_fmt = 'PID:{pid} name:{name} state:{state}\n'
my_fmt += ' stack used {stack_used} of {stack_limit}\n'
if t.is_waiting:
my_fmt += ' waiting for {waiting_for}\n'
my_fmt += ' open files: {file_descriptors}\n'
my_fmt += ' R0 {registers[R0]:#010x} {registers[R1]:#010x} {registers[R2]:#010x} {registers[R3]:#010x}\n'
my_fmt += ' R4 {registers[R4]:#010x} {registers[R5]:#010x} {registers[R6]:#010x} {registers[R7]:#010x}\n'
my_fmt += ' R8 {registers[R8]:#010x} {registers[R9]:#010x} {registers[R10]:#010x} {registers[R11]:#010x}\n'
my_fmt += ' R12 {registers[PC]:#010x}\n'
my_fmt += ' SP {registers[SP]:#010x} LR {registers[LR]:#010x} PC {registers[PC]:#010x} XPSR {registers[XPSR]:#010x}\n'
print format(t, my_fmt)
class NX_show_tasks (gdb.Command):
"""(NuttX) prints a list of tasks"""
def __init__(self):
super(NX_show_tasks, self).__init__('show tasks', gdb.COMMAND_USER)
def invoke(self, args, from_tty):
tasks = NX_task.tasks()
for t in tasks:
print format(t, '{pid:<2} {name:<16} {state:<20} {stack_used:>4}/{stack_limit:<4}')
NX_show_task()
NX_show_tasks()
class NX_show_heap (gdb.Command):
"""(NuttX) prints the heap"""
def __init__(self):
super(NX_show_heap, self).__init__('show heap', gdb.COMMAND_USER)
if gdb.lookup_type('struct mm_allocnode_s').sizeof == 8:
self._allocflag = 0x80000000
self._allocnodesize = 8
else:
self._allocflag = 0x8000
self._allocnodesize = 4
def _node_allocated(self, allocnode):
if allocnode['preceding'] & self._allocflag:
return True
return False
def _node_size(self, allocnode):
return allocnode['size'] & ~self._allocflag
def _print_allocations(self, region_start, region_end):
if region_start >= region_end:
print 'heap region {} corrupt'.format(hex(region_start))
return
nodecount = region_end - region_start
print 'heap {} - {}'.format(region_start, region_end)
cursor = 1
while cursor < nodecount:
allocnode = region_start[cursor]
if self._node_allocated(allocnode):
state = ''
else:
state = '(free)'
print ' {} {} {}'.format(allocnode.address + 8, self._node_size(allocnode), state)
cursor += self._node_size(allocnode) / self._allocnodesize
def invoke(self, args, from_tty):
heap = gdb.lookup_global_symbol('g_mmheap').value()
nregions = heap['mm_nregions']
region_starts = heap['mm_heapstart']
region_ends = heap['mm_heapend']
print "{} heap(s)".format(nregions)
# walk the heaps
for i in range(0, nregions):
self._print_allocations(region_starts[i], region_ends[i])
NX_show_heap()
+6 -7
View File
@@ -429,19 +429,19 @@ SORT_BY_SCOPE_NAME = NO
# disable (NO) the todo list. This list is created by putting \todo
# commands in the documentation.
GENERATE_TODOLIST = YES
GENERATE_TODOLIST = NO
# The GENERATE_TESTLIST tag can be used to enable (YES) or
# disable (NO) the test list. This list is created by putting \test
# commands in the documentation.
GENERATE_TESTLIST = YES
GENERATE_TESTLIST = NO
# The GENERATE_BUGLIST tag can be used to enable (YES) or
# disable (NO) the bug list. This list is created by putting \bug
# commands in the documentation.
GENERATE_BUGLIST = YES
GENERATE_BUGLIST = NO
# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or
# disable (NO) the deprecated list. This list is created by putting
@@ -569,7 +569,7 @@ WARN_LOGFILE = doxy.log
# directories like "/usr/src/myproject". Separate the files or directories
# with spaces.
INPUT = ../apps
INPUT = ../src
# This tag can be used to specify the character encoding of the source files
# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is
@@ -599,9 +599,8 @@ RECURSIVE = YES
# excluded from the INPUT source files. This way you can easily exclude a
# subdirectory from a directory tree whose root is specified with the INPUT tag.
EXCLUDE = ../dist/ \
../docs/html/ \
html
EXCLUDE = ../src/modules/mathlib/CMSIS \
../src/modules/attitude_estimator_ekf/codegen
# The EXCLUDE_SYMLINKS tag can be used select whether or not files or
# directories that are symbolic links (a Unix filesystem feature) are excluded
Binary file not shown.
Binary file not shown.
File diff suppressed because it is too large Load Diff
Binary file not shown.
Binary file not shown.
+2 -1
View File
@@ -32,7 +32,8 @@
"settings":
{
"tab_size": 8,
"translate_tabs_to_spaces": false
"translate_tabs_to_spaces": false,
"highlight_line": true
},
"build_systems":
[
+82 -42
View File
@@ -100,7 +100,7 @@ all: $(STAGED_FIRMWARES)
# is taken care of.
#
$(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
@echo %% Copying $@
@$(ECHO) %% Copying $@
$(Q) $(COPY) $< $@
$(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@)
@@ -111,9 +111,9 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
@echo %%%%
@echo %%%% Building $(config) in $(work_dir)
@echo %%%%
@$(ECHO) %%%%
@$(ECHO) %%%% Building $(config) in $(work_dir)
@$(ECHO) %%%%
$(Q) mkdir -p $(work_dir)
$(Q) make -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
@@ -132,8 +132,6 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
# XXX Should support fetching/unpacking from a separate directory to permit
# downloads of the prebuilt archives as well...
#
# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4"
#
NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
.PHONY: archives
archives: $(NUTTX_ARCHIVES)
@@ -146,15 +144,54 @@ endif
$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
$(ARCHIVE_DIR)%.export: configuration = nsh
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS)
@echo %% Configuring NuttX for $(board)
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@echo %% Exporting NuttX for $(board)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export
@$(ECHO) %% Exporting NuttX for $(board)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
$(Q) mkdir -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
#
# The user can run the NuttX 'menuconfig' tool for a single board configuration with
# make BOARDS=<boardname> menuconfig
#
ifeq ($(MAKECMDGOALS),menuconfig)
ifneq ($(words $(BOARDS)),1)
$(error BOARDS must specify exactly one board for the menuconfig goal)
endif
BOARD = $(BOARDS)
menuconfig: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(BOARD)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
@$(ECHO) %% Running menuconfig for $(BOARD)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
@$(ECHO) %% Saving configuration file
$(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
else
menuconfig:
@$(ECHO) ""
@$(ECHO) "The menuconfig goal must be invoked without any other goal being specified"
@$(ECHO) ""
endif
$(NUTTX_SRC):
@$(ECHO) ""
@$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again."
@$(ECHO) ""
#
# Testing targets
#
testbuild:
$(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8)
#
# Cleanup targets. 'clean' should remove all built products and force
@@ -176,40 +213,43 @@ distclean: clean
#
.PHONY: help
help:
@echo ""
@echo " PX4 firmware builder"
@echo " ===================="
@echo ""
@echo " Available targets:"
@echo " ------------------"
@echo ""
@echo " archives"
@echo " Build the NuttX RTOS archives that are used by the firmware build."
@echo ""
@echo " all"
@echo " Build all firmware configs: $(CONFIGS)"
@echo " A limited set of configs can be built with CONFIGS=<list-of-configs>"
@echo ""
@$(ECHO) ""
@$(ECHO) " PX4 firmware builder"
@$(ECHO) " ===================="
@$(ECHO) ""
@$(ECHO) " Available targets:"
@$(ECHO) " ------------------"
@$(ECHO) ""
@$(ECHO) " archives"
@$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build."
@$(ECHO) ""
@$(ECHO) " all"
@$(ECHO) " Build all firmware configs: $(CONFIGS)"
@$(ECHO) " A limited set of configs can be built with CONFIGS=<list-of-configs>"
@$(ECHO) ""
@for config in $(CONFIGS); do \
echo " $$config"; \
echo " Build just the $$config firmware configuration."; \
echo ""; \
done
@echo " clean"
@echo " Remove all firmware build pieces."
@echo ""
@echo " distclean"
@echo " Remove all compilation products, including NuttX RTOS archives."
@echo ""
@echo " upload"
@echo " When exactly one config is being built, add this target to upload the"
@echo " firmware to the board when the build is complete. Not supported for"
@echo " all configurations."
@echo ""
@echo " Common options:"
@echo " ---------------"
@echo ""
@echo " V=1"
@echo " If V is set, more verbose output is printed during the build. This can"
@echo " help when diagnosing issues with the build or toolchain."
@echo ""
@$(ECHO) " clean"
@$(ECHO) " Remove all firmware build pieces."
@$(ECHO) ""
@$(ECHO) " distclean"
@$(ECHO) " Remove all compilation products, including NuttX RTOS archives."
@$(ECHO) ""
@$(ECHO) " upload"
@$(ECHO) " When exactly one config is being built, add this target to upload the"
@$(ECHO) " firmware to the board when the build is complete. Not supported for"
@$(ECHO) " all configurations."
@$(ECHO) ""
@$(ECHO) " testbuild"
@$(ECHO) " Perform a complete clean build of the entire tree."
@$(ECHO) ""
@$(ECHO) " Common options:"
@$(ECHO) " ---------------"
@$(ECHO) ""
@$(ECHO) " V=1"
@$(ECHO) " If V is set, more verbose output is printed during the build. This can"
@$(ECHO) " help when diagnosing issues with the build or toolchain."
@$(ECHO) ""
+122
View File
@@ -0,0 +1,122 @@
#!nsh
#
# Flight startup script for PX4FMU+PX4IO
#
# disable USB and autostart
set USB no
set MODE custom
#
# Start the ORB (first app to start)
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/params
fi
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
param save /fs/microsd/params
fi
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 10
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
if [ -f /fs/microsd/px4io.bin ]
then
echo "PX4IO Firmware found. Checking Upgrade.."
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
then
echo "No newer version, skipping upgrade."
else
echo "Loading /fs/microsd/px4io.bin"
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
then
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
else
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
fi
fi
fi
#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start the commander (depends on orb, mavlink)
#
commander start
#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
#
# Disable px4io topic limiting
#
px4io limit 200
#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator (depends on orb)
#
attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
md25 start 3 0x58
segway start
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi
Binary file not shown.
-586
View File
@@ -1,586 +0,0 @@
% This Matlab Script can be used to import the binary logged values of the
% PX4FMU into data that can be plotted and analyzed.
%% ************************************************************************
% PX4LOG_PLOTSCRIPT: Main function
% ************************************************************************
function PX4Log_Plotscript
% Clear everything
clc
clear all
close all
% ************************************************************************
% SETTINGS
% ************************************************************************
% Set the path to your sysvector.bin file here
filePath = 'sysvector.bin';
% Set the minimum and maximum times to plot here [in seconds]
mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start]
maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end]
%Determine which data to plot. Not completely implemented yet.
bDisplayGPS=true;
%conversion factors
fconv_gpsalt=1E-3; %[mm] to [m]
fconv_gpslatlong=1E-7; %[gps_raw_position_unit] to [deg]
fconv_timestamp=1E-6; % [microseconds] to [seconds]
% ************************************************************************
% Import the PX4 logs
% ************************************************************************
ImportPX4LogData();
%Translate min and max plot times to indices
time=double(sysvector.timestamp) .*fconv_timestamp;
mintime_log=time(1); %The minimum time/timestamp found in the log
maxtime_log=time(end); %The maximum time/timestamp found in the log
CurTime=mintime_log; %The current time at which to draw the aircraft position
[imintime,imaxtime]=FindMinMaxTimeIndices();
% ************************************************************************
% PLOT & GUI SETUP
% ************************************************************************
NrFigures=5;
NrAxes=10;
h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively
h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively
h.pathpoints=[]; % Temporary initiliazation of path points
% Setup the GUI to control the plots
InitControlGUI();
% Setup the plotting-GUI (figures, axes) itself.
InitPlotGUI();
% ************************************************************************
% DRAW EVERYTHING
% ************************************************************************
DrawRawData();
DrawCurrentAircraftState();
%% ************************************************************************
% *** END OF MAIN SCRIPT ***
% NESTED FUNCTION DEFINTIONS FROM HERE ON
% ************************************************************************
%% ************************************************************************
% IMPORTPX4LOGDATA (nested function)
% ************************************************************************
% Attention: This is the import routine for firmware from ca. 03/2013.
% Other firmware versions might require different import
% routines.
function ImportPX4LogData()
% Work around a Matlab bug (not related to PX4)
% where timestamps from 1.1.1970 do not allow to
% read the file's size
if ismac
system('touch -t 201212121212.12 sysvector.bin');
end
% ************************************************************************
% RETRIEVE SYSTEM VECTOR
% *************************************************************************
% //All measurements in NED frame
%
% uint64_t timestamp; //[us]
% float gyro[3]; //[rad/s]
% float accel[3]; //[m/s^2]
% float mag[3]; //[gauss]
% float baro; //pressure [millibar]
% float baro_alt; //altitude above MSL [meter]
% float baro_temp; //[degree celcius]
% float control[4]; //roll, pitch, yaw [-1..1], thrust [0..1]
% float actuators[8]; //motor 1-8, in motor units (PWM: 1000-2000,AR.Drone: 0-512)
% float vbat; //battery voltage in [volt]
% float bat_current - current drawn from battery at this time instant
% float bat_discharged - discharged energy in mAh
% float adc[4]; //remaining auxiliary ADC ports [volt]
% float local_position[3]; //tangent plane mapping into x,y,z [m]
% int32_t gps_raw_position[3]; //latitude [degrees] north, longitude [degrees] east, altitude above MSL [millimeter]
% float attitude[3]; //pitch, roll, yaw [rad]
% float rotMatrix[9]; //unitvectors
% float actuator_control[4]; //unitvector
% float optical_flow[4]; //roll, pitch, yaw [-1..1], thrust [0..1]
% float diff_pressure; - pressure difference in millibar
% float ind_airspeed;
% float true_airspeed;
% Definition of the logged values
logFormat{1} = struct('name', 'timestamp', 'bytes', 8, 'array', 1, 'precision', 'uint64', 'machineformat', 'ieee-le.l64');
logFormat{2} = struct('name', 'gyro', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{3} = struct('name', 'accel', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{4} = struct('name', 'mag', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{5} = struct('name', 'baro', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{6} = struct('name', 'baro_alt', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{7} = struct('name', 'baro_temp', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{8} = struct('name', 'control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{9} = struct('name', 'actuators', 'bytes', 4, 'array', 8, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{10} = struct('name', 'vbat', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{11} = struct('name', 'bat_current', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{12} = struct('name', 'bat_discharged', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{13} = struct('name', 'adc', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{14} = struct('name', 'local_position', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{15} = struct('name', 'gps_raw_position', 'bytes', 4, 'array', 3, 'precision', 'uint32', 'machineformat', 'ieee-le');
logFormat{16} = struct('name', 'attitude', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{17} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{18} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{19} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{20} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{21} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{22} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{23} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
% First get length of one line
columns = length(logFormat);
lineLength = 0;
for i=1:columns
lineLength = lineLength + logFormat{i}.bytes * logFormat{i}.array;
end
if exist(filePath, 'file')
fileInfo = dir(filePath);
fileSize = fileInfo.bytes;
elements = int64(fileSize./(lineLength));
fid = fopen(filePath, 'r');
offset = 0;
for i=1:columns
% using fread with a skip speeds up the import drastically, do not
% import the values one after the other
sysvector.(genvarname(logFormat{i}.name)) = transpose(fread(...
fid, ...
[logFormat{i}.array, elements], [num2str(logFormat{i}.array),'*',logFormat{i}.precision,'=>',logFormat{i}.precision], ...
lineLength - logFormat{i}.bytes*logFormat{i}.array, ...
logFormat{i}.machineformat) ...
);
offset = offset + logFormat{i}.bytes*logFormat{i}.array;
fseek(fid, offset,'bof');
end
% shot the flight time
time_us = sysvector.timestamp(end) - sysvector.timestamp(1);
time_s = time_us*1e-6;
time_m = time_s/60;
% close the logfile
fclose(fid);
disp(['end log2matlab conversion' char(10)]);
else
disp(['file: ' filePath ' does not exist' char(10)]);
end
end
%% ************************************************************************
% INITCONTROLGUI (nested function)
% ************************************************************************
%Setup central control GUI components to control current time where data is shown
function InitControlGUI()
%**********************************************************************
% GUI size definitions
%**********************************************************************
dxy=5; %margins
%Panel: Plotctrl
dlabels=120;
dsliders=200;
dedits=80;
hslider=20;
hpanel1=40; %panel1
hpanel2=220;%panel2
hpanel3=3*hslider+4*dxy+3*dxy;%panel3.
width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width
height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height
%**********************************************************************
% Create GUI
%**********************************************************************
h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI');
h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1));
h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1));
h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1));
%%Control GUI-elements
%Slider: Current time
h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left');
h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],...
'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel);
temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min');
set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]);
h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),...
'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel);
%Slider: MaxTime
h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left');
h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],...
'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel);
h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),...
'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel);
%Slider: MinTime
h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left');
h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],...
'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel);
h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),...
'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel);
%%Current data/state GUI-elements (Multiline-edit-box)
h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',...
'HorizontalAlignment','left','parent',h.aircraftstatepanel);
h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',...
'HorizontalAlignment','left','parent',h.guistatepanel);
end
%% ************************************************************************
% INITPLOTGUI (nested function)
% ************************************************************************
function InitPlotGUI()
% Setup handles to lines and text
h.markertext=[];
templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array
h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively
h.markerline(1:NrAxes)=0.0;
% Setup all other figures and axes for plotting
% PLOT WINDOW 1: GPS POSITION
h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position');
h.axes(1)=axes();
set(h.axes(1),'Parent',h.figures(2));
% PLOT WINDOW 2: IMU, baro altitude
h.figures(3)=figure('Name', 'IMU / Baro Altitude');
h.axes(2)=subplot(4,1,1);
h.axes(3)=subplot(4,1,2);
h.axes(4)=subplot(4,1,3);
h.axes(5)=subplot(4,1,4);
set(h.axes(2:5),'Parent',h.figures(3));
% PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,...
h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds');
h.axes(6)=subplot(4,1,1);
h.axes(7)=subplot(4,1,2);
h.axes(8)=subplot(4,1,3);
h.axes(9)=subplot(4,1,4);
set(h.axes(6:9),'Parent',h.figures(4));
% PLOT WINDOW 4: LOG STATS
h.figures(5) = figure('Name', 'Log Statistics');
h.axes(10)=subplot(1,1,1);
set(h.axes(10:10),'Parent',h.figures(5));
end
%% ************************************************************************
% DRAWRAWDATA (nested function)
% ************************************************************************
%Draws the raw data from the sysvector, but does not add any
%marker-lines or so
function DrawRawData()
% ************************************************************************
% PLOT WINDOW 1: GPS POSITION & GUI
% ************************************************************************
figure(h.figures(2));
% Only plot GPS data if available
if (sum(double(sysvector.gps_raw_position(imintime:imaxtime,1)))>0) && (bDisplayGPS)
%Draw data
plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:imaxtime,1))*fconv_gpslatlong, ...
double(sysvector.gps_raw_position(imintime:imaxtime,2))*fconv_gpslatlong, ...
double(sysvector.gps_raw_position(imintime:imaxtime,3))*fconv_gpsalt,'r.');
title(h.axes(1),'GPS Position Data(if available)');
xlabel(h.axes(1),'Latitude [deg]');
ylabel(h.axes(1),'Longitude [deg]');
zlabel(h.axes(1),'Altitude above MSL [m]');
grid on
%Reset path
h.pathpoints=0;
end
% ************************************************************************
% PLOT WINDOW 2: IMU, baro altitude
% ************************************************************************
figure(h.figures(3));
plot(h.axes(2),time(imintime:imaxtime),sysvector.mag(imintime:imaxtime,:));
title(h.axes(2),'Magnetometers [Gauss]');
legend(h.axes(2),'x','y','z');
plot(h.axes(3),time(imintime:imaxtime),sysvector.accel(imintime:imaxtime,:));
title(h.axes(3),'Accelerometers [m/s²]');
legend(h.axes(3),'x','y','z');
plot(h.axes(4),time(imintime:imaxtime),sysvector.gyro(imintime:imaxtime,:));
title(h.axes(4),'Gyroscopes [rad/s]');
legend(h.axes(4),'x','y','z');
plot(h.axes(5),time(imintime:imaxtime),sysvector.baro_alt(imintime:imaxtime),'color','blue');
if(bDisplayGPS)
hold on;
plot(h.axes(5),time(imintime:imaxtime),double(sysvector.gps_raw_position(imintime:imaxtime,3)).*fconv_gpsalt,'color','red');
hold off
legend('Barometric Altitude [m]','GPS Altitude [m]');
else
legend('Barometric Altitude [m]');
end
title(h.axes(5),'Altitude above MSL [m]');
% ************************************************************************
% PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,...
% ************************************************************************
figure(h.figures(4));
%Attitude Estimate
plot(h.axes(6),time(imintime:imaxtime), sysvector.attitude(imintime:imaxtime,:).*180./3.14159);
title(h.axes(6),'Estimated attitude [deg]');
legend(h.axes(6),'roll','pitch','yaw');
%Actuator Controls
plot(h.axes(7),time(imintime:imaxtime), sysvector.actuator_control(imintime:imaxtime,:));
title(h.axes(7),'Actuator control [-]');
legend(h.axes(7),'0','1','2','3');
%Actuator Controls
plot(h.axes(8),time(imintime:imaxtime), sysvector.actuators(imintime:imaxtime,1:8));
title(h.axes(8),'Actuator PWM (raw-)outputs [µs]');
legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8');
set(h.axes(8), 'YLim',[800 2200]);
%Airspeeds
plot(h.axes(9),time(imintime:imaxtime), sysvector.ind_airspeed(imintime:imaxtime));
hold on
plot(h.axes(9),time(imintime:imaxtime), sysvector.true_airspeed(imintime:imaxtime));
hold off
%add GPS total airspeed here
title(h.axes(9),'Airspeed [m/s]');
legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed');
%calculate time differences and plot them
intervals = zeros(0,imaxtime - imintime);
for k = imintime+1:imaxtime
intervals(k) = time(k) - time(k-1);
end
plot(h.axes(10), time(imintime:imaxtime), intervals);
%Set same timescale for all plots
for i=2:NrAxes
set(h.axes(i),'XLim',[mintime maxtime]);
end
set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]);
end
%% ************************************************************************
% DRAWCURRENTAIRCRAFTSTATE(nested function)
% ************************************************************************
function DrawCurrentAircraftState()
%find current data index
i=find(time>=CurTime,1,'first');
%**********************************************************************
% Current aircraft state label update
%**********************************************************************
acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong),'°, ',...
'lon=',num2str(double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong),'°, ',...
'alt=',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]'];
acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.mag(i,1)),...
', y=',num2str(sysvector.mag(i,2)),...
', z=',num2str(sysvector.mag(i,3)),']'];
acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.accel(i,1)),...
', y=',num2str(sysvector.accel(i,2)),...
', z=',num2str(sysvector.accel(i,3)),']'];
acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.gyro(i,1)),...
', y=',num2str(sysvector.gyro(i,2)),...
', z=',num2str(sysvector.gyro(i,3)),']'];
acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.baro_alt(i)),'m, GPS: ',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]'];
acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.attitude(i,1).*180./3.14159),...
', Pitch=',num2str(sysvector.attitude(i,2).*180./3.14159),...
', Yaw=',num2str(sysvector.attitude(i,3).*180./3.14159),']'];
acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:');
for j=1:4
acstate{7,:}=[acstate{7,:},num2str(sysvector.actuator_control(i,j)),','];
end
acstate{7,:}=[acstate{7,:},']'];
acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:');
for j=1:8
acstate{8,:}=[acstate{8,:},num2str(sysvector.actuators(i,j)),','];
end
acstate{8,:}=[acstate{8,:},']'];
acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.ind_airspeed(i)),', TAS: ',num2str(sysvector.true_airspeed(i)),']'];
set(h.edits.AircraftState,'String',acstate);
%**********************************************************************
% GPS Plot Update
%**********************************************************************
%Plot traveled path, and and time.
figure(h.figures(2));
hold on;
if(CurTime>mintime+1) %the +1 is only a small bugfix
h.pathline=plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:i,1))*fconv_gpslatlong, ...
double(sysvector.gps_raw_position(imintime:i,2))*fconv_gpslatlong, ...
double(sysvector.gps_raw_position(imintime:i,3))*fconv_gpsalt,'b','LineWidth',2);
end;
hold off
%Plot current position
newpoint=[double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong double(sysvector.gps_raw_position(i,3))*fconv_gpsalt];
if(numel(h.pathpoints)<=3) %empty path
h.pathpoints(1,1:3)=newpoint;
else %Not empty, append new point
h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint;
end
axes(h.axes(1));
line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20);
% Plot current time (small label next to current gps position)
textdesc=strcat(' t=',num2str(time(i)),'s');
if(isvalidhandle(h.markertext))
delete(h.markertext); %delete old text
end
h.markertext=text(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong,double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong,...
double(sysvector.gps_raw_position(i,3))*fconv_gpsalt,textdesc);
set(h.edits.CurTime,'String',CurTime);
%**********************************************************************
% Plot the lines showing the current time in the 2-d plots
%**********************************************************************
for i=2:NrAxes
if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end
ylims=get(h.axes(i),'YLim');
h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black');
set(h.markerline(i),'parent',h.axes(i));
end
set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]);
end
%% ************************************************************************
% MINMAXTIME CALLBACK (nested function)
% ************************************************************************
function minmaxtime_callback(hObj,event) %#ok<INUSL>
new_mintime=get(h.sliders.MinTime,'Value');
new_maxtime=get(h.sliders.MaxTime,'Value');
%Safety checks:
bErr=false;
%1: mintime must be < maxtime
if((new_mintime>maxtime) || (new_maxtime<mintime))
set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than maxtime! Values were not changed.','BackgroundColor','red');
bErr=true;
else
%2: MinTime must be <=CurTime
if(new_mintime>CurTime)
set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red');
mintime=new_mintime;
CurTime=mintime;
bErr=true;
end
%3: MaxTime must be >CurTime
if(new_maxtime<CurTime)
set(h.labels.GUIState,'String','Error: Maxtime cannot be smaller than CurTime! CurTime set to new maxtime.','BackgroundColor','red');
maxtime=new_maxtime;
CurTime=maxtime;
bErr=true;
end
end
if(bErr==false)
maxtime=new_maxtime;
mintime=new_mintime;
end
%Needs to be done in case values were reset above
set(h.sliders.MinTime,'Value',mintime);
set(h.sliders.MaxTime,'Value',maxtime);
%Update curtime-slider
set(h.sliders.CurTime,'Value',CurTime);
set(h.sliders.CurTime,'Max',maxtime);
set(h.sliders.CurTime,'Min',mintime);
temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min');
set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); %Set Stepsize to constant [in seconds]
%update edit fields
set(h.edits.CurTime,'String',get(h.sliders.CurTime,'Value'));
set(h.edits.MinTime,'String',get(h.sliders.MinTime,'Value'));
set(h.edits.MaxTime,'String',get(h.sliders.MaxTime,'Value'));
%Finally, we have to redraw. Update time indices first.
[imintime,imaxtime]=FindMinMaxTimeIndices();
DrawRawData(); %Rawdata only
DrawCurrentAircraftState(); %path info & markers
end
%% ************************************************************************
% CURTIME CALLBACK (nested function)
% ************************************************************************
function curtime_callback(hObj,event) %#ok<INUSL>
%find current time
if(hObj==h.sliders.CurTime)
CurTime=get(h.sliders.CurTime,'Value');
elseif (hObj==h.edits.CurTime)
temp=str2num(get(h.edits.CurTime,'String'));
if(temp<maxtime && temp>mintime)
CurTime=temp;
else
%Error
set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red');
end
else
%Error
set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red');
end
set(h.sliders.CurTime,'Value',CurTime);
set(h.edits.CurTime,'String',num2str(CurTime));
%Redraw time markers, but don't have to redraw the whole raw data
DrawCurrentAircraftState();
end
%% ************************************************************************
% FINDMINMAXINDICES (nested function)
% ************************************************************************
function [idxmin,idxmax] = FindMinMaxTimeIndices()
for i=1:size(sysvector.timestamp,1)
if time(i)>=mintime; idxmin=i; break; end
end
for i=1:size(sysvector.timestamp,1)
if maxtime==0; idxmax=size(sysvector.timestamp,1); break; end
if time(i)>=maxtime; idxmax=i; break; end
end
mintime=time(idxmin);
maxtime=time(idxmax);
end
%% ************************************************************************
% ISVALIDHANDLE (nested function)
% ************************************************************************
function isvalid = isvalidhandle(handle)
if(exist(varname(handle))>0 && length(ishandle(handle))>0)
if(ishandle(handle)>0)
if(handle>0.0)
isvalid=true;
return;
end
end
end
isvalid=false;
end
%% ************************************************************************
% JUST SOME SMALL HELPER FUNCTIONS (nested function)
% ************************************************************************
function out = varname(var)
out = inputname(1);
end
%This is the end of the matlab file / the main function
end
+13
View File
@@ -0,0 +1,13 @@
====== PX4 LOG CONVERSION ======
On each log session (commonly started and stopped by arming and disarming the vehicle) a new file logxxx.bin is created. In many cases there will be only one logfile named log001.bin (only one flight).
There are two conversion scripts in this ZIP file:
logconv.m: This is a MATLAB script which will automatically convert and display the flight data with a GUI. If running this script, the second script can be ignored.
sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run:
python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n ""
Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux.
+3 -2
View File
@@ -16,7 +16,7 @@ close all
% ************************************************************************
% Set the path to your sysvector.bin file here
filePath = 'log_second_flight.bin';
filePath = 'log001.bin';
% Set the minimum and maximum times to plot here [in seconds]
mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start]
@@ -111,8 +111,9 @@ function ImportPX4LogData()
time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1);
time_s = uint64(time_us*1e-6);
time_m = uint64(time_s/60);
time_s = time_s - time_m * 60;
disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]);
disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]);
disp(['logfile conversion finished.' char(10)]);
else
-59
View File
@@ -1,59 +0,0 @@
#!/usr/bin/env python
"""Convert binary log generated by sdlog to CSV format
Usage: python logconv.py <log.bin>"""
__author__ = "Anton Babushkin"
__version__ = "0.1"
import struct, sys
def _unpack_packet(data):
s = ""
s += "Q" #.timestamp = buf.raw.timestamp,
s += "fff" #.gyro = {buf.raw.gyro_rad_s[0], buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2]},
s += "fff" #.accel = {buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1], buf.raw.accelerometer_m_s2[2]},
s += "fff" #.mag = {buf.raw.magnetometer_ga[0], buf.raw.magnetometer_ga[1], buf.raw.magnetometer_ga[2]},
s += "f" #.baro = buf.raw.baro_pres_mbar,
s += "f" #.baro_alt = buf.raw.baro_alt_meter,
s += "f" #.baro_temp = buf.raw.baro_temp_celcius,
s += "ffff" #.control = {buf.act_controls.control[0], buf.act_controls.control[1], buf.act_controls.control[2], buf.act_controls.control[3]},
s += "ffffffff" #.actuators = {buf.act_outputs.output[0], buf.act_outputs.output[1], buf.act_outputs.output[2], buf.act_outputs.output[3], buf.act_outputs.output[4], buf.act_outputs.output[5], buf.act_outputs.output[6], buf.act_outputs.output[7]},
s += "f" #.vbat = buf.batt.voltage_v,
s += "f" #.bat_current = buf.batt.current_a,
s += "f" #.bat_discharged = buf.batt.discharged_mah,
s += "ffff" #.adc = {buf.raw.adc_voltage_v[0], buf.raw.adc_voltage_v[1], buf.raw.adc_voltage_v[2], buf.raw.adc_voltage_v[3]},
s += "fff" #.local_position = {buf.local_pos.x, buf.local_pos.y, buf.local_pos.z},
s += "iii" #.gps_raw_position = {buf.gps_pos.lat, buf.gps_pos.lon, buf.gps_pos.alt},
s += "fff" #.attitude = {buf.att.pitch, buf.att.roll, buf.att.yaw},
s += "fffffffff" #.rotMatrix = {buf.att.R[0][0], buf.att.R[0][1], buf.att.R[0][2], buf.att.R[1][0], buf.att.R[1][1], buf.att.R[1][2], buf.att.R[2][0], buf.att.R[2][1], buf.att.R[2][2]},
s += "fff" #.vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw},
s += "ffff" #.control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]},
s += "ffffff" #.flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality},
s += "f" #.diff_pressure = buf.diff_pres.differential_pressure_pa,
s += "f" #.ind_airspeed = buf.airspeed.indicated_airspeed_m_s,
s += "f" #.true_airspeed = buf.airspeed.true_airspeed_m_s
s += "iii" # to align to 280
d = struct.unpack(s, data)
return d
def _main():
if len(sys.argv) < 2:
print "Usage:\npython logconv.py <log.bin>"
return
fn = sys.argv[1]
sysvector_size = 280
f = open(fn, "r")
while True:
data = f.read(sysvector_size)
if len(data) < sysvector_size:
break
a = []
for i in _unpack_packet(data):
a.append(str(i))
print ";".join(a)
f.close()
if __name__ == "__main__":
_main()
+47 -29
View File
@@ -1,6 +1,8 @@
#!/usr/bin/env python
"""Dump binary log generated by sdlog2 or APM as CSV
from __future__ import print_function
"""Dump binary log generated by PX4's sdlog2 or APM as CSV
Usage: python sdlog2_dump.py <log.bin> [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]]
@@ -21,6 +23,11 @@ __version__ = "1.2"
import struct, sys
if sys.hexversion >= 0x030000F0:
runningPython3 = True
else:
runningPython3 = False
class SDLog2Parser:
BLOCK_SIZE = 8192
MSG_HEADER_LEN = 3
@@ -65,7 +72,7 @@ class SDLog2Parser:
self.__msg_descrs = {} # message descriptions by message type map
self.__msg_labels = {} # message labels by message name map
self.__msg_names = [] # message names in the same order as FORMAT messages
self.__buffer = "" # buffer for input binary data
self.__buffer = bytearray() # buffer for input binary data
self.__ptr = 0 # read pointer in buffer
self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label"
self.__csv_data = {} # current values for all columns
@@ -105,7 +112,7 @@ class SDLog2Parser:
for msg_name, show_fields in self.__msg_filter:
self.__msg_filter_map[msg_name] = show_fields
first_data_msg = True
f = open(fn, "r")
f = open(fn, "rb")
bytes_read = 0
while True:
chunk = f.read(self.BLOCK_SIZE)
@@ -114,15 +121,15 @@ class SDLog2Parser:
self.__buffer = self.__buffer[self.__ptr:] + chunk
self.__ptr = 0
while self.__bytesLeft() >= self.MSG_HEADER_LEN:
head1 = ord(self.__buffer[self.__ptr])
head2 = ord(self.__buffer[self.__ptr+1])
head1 = self.__buffer[self.__ptr]
head2 = self.__buffer[self.__ptr+1]
if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2):
if self.__correct_errors:
self.__ptr += 1
continue
else:
raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2))
msg_type = ord(self.__buffer[self.__ptr+2])
msg_type = self.__buffer[self.__ptr+2]
if msg_type == self.MSG_TYPE_FORMAT:
# parse FORMAT message
if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN:
@@ -168,9 +175,9 @@ class SDLog2Parser:
self.__csv_columns.append(full_label)
self.__csv_data[full_label] = None
if self.__file != None:
print >> self.__file, self.__csv_delim.join(self.__csv_columns)
print(self.__csv_delim.join(self.__csv_columns), file=self.__file)
else:
print self.__csv_delim.join(self.__csv_columns)
print(self.__csv_delim.join(self.__csv_columns))
def __printCSVRow(self):
s = []
@@ -183,18 +190,26 @@ class SDLog2Parser:
s.append(v)
if self.__file != None:
print >> self.__file, self.__csv_delim.join(s)
print(self.__csv_delim.join(s), file=self.__file)
else:
print self.__csv_delim.join(s)
print(self.__csv_delim.join(s))
def __parseMsgDescr(self):
data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])
if runningPython3:
data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])
else:
data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]))
msg_type = data[0]
if msg_type != self.MSG_TYPE_FORMAT:
msg_length = data[1]
msg_name = data[2].strip("\0")
msg_format = data[3].strip("\0")
msg_labels = data[4].strip("\0").split(",")
if runningPython3:
msg_name = str(data[2], 'ascii').strip("\0")
msg_format = str(data[3], 'ascii').strip("\0")
msg_labels = str(data[4], 'ascii').strip("\0").split(",")
else:
msg_name = str(data[2]).strip("\0")
msg_format = str(data[3]).strip("\0")
msg_labels = str(data[4]).strip("\0").split(",")
# Convert msg_format to struct.unpack format string
msg_struct = ""
msg_mults = []
@@ -211,8 +226,8 @@ class SDLog2Parser:
self.__msg_names.append(msg_name)
if self.__debug_out:
if self.__filterMsg(msg_name) != None:
print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % (
msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)
print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % (
msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults))
self.__ptr += self.MSG_FORMAT_PACKET_LEN
def __parseMsg(self, msg_descr):
@@ -222,8 +237,11 @@ class SDLog2Parser:
self.__csv_updated = False
show_fields = self.__filterMsg(msg_name)
if (show_fields != None):
data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))
for i in xrange(len(data)):
if runningPython3:
data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))
else:
data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))
for i in range(len(data)):
if type(data[i]) is str:
data[i] = data[i].strip("\0")
m = msg_mults[i]
@@ -231,14 +249,14 @@ class SDLog2Parser:
data[i] = data[i] * m
if self.__debug_out:
s = []
for i in xrange(len(data)):
for i in range(len(data)):
label = msg_labels[i]
if show_fields == "*" or label in show_fields:
s.append(label + "=" + str(data[i]))
print "MSG %s: %s" % (msg_name, ", ".join(s))
print("MSG %s: %s" % (msg_name, ", ".join(s)))
else:
# update CSV data buffer
for i in xrange(len(data)):
for i in range(len(data)):
label = msg_labels[i]
if label in show_fields:
self.__csv_data[msg_name + "_" + label] = data[i]
@@ -250,14 +268,14 @@ class SDLog2Parser:
def _main():
if len(sys.argv) < 2:
print "Usage: python sdlog2_dump.py <log.bin> [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n"
print "\t-v\tUse plain debug output instead of CSV.\n"
print "\t-e\tRecover from errors.\n"
print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n"
print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n"
print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed."
print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n"
print "\t-fPrint to file instead of stdout"
print("Usage: python sdlog2_dump.py <log.bin> [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n")
print("\t-v\tUse plain debug output instead of CSV.\n")
print("\t-e\tRecover from errors.\n")
print("\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n")
print("\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n")
print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.")
print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n")
print("\t-fPrint to file instead of stdout")
return
fn = sys.argv[1]
debug_out = False
+1
View File
@@ -6,5 +6,6 @@
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM4F
CONFIG_BOARD = PX4FMU_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
+1
View File
@@ -6,5 +6,6 @@
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM3
CONFIG_BOARD = PX4IO_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
+2
View File
@@ -75,6 +75,7 @@ MODULES += examples/flow_position_estimator
#
# Vehicle Control
#
MODULES += modules/segway
MODULES += modules/fixedwing_backside
MODULES += modules/fixedwing_att_control
MODULES += modules/fixedwing_pos_control
@@ -96,6 +97,7 @@ MODULES += modules/sdlog2
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/mathlib
MODULES += modules/mathlib/math/filter
MODULES += modules/controllib
MODULES += modules/uORB
+2 -1
View File
@@ -153,6 +153,7 @@ ifeq ($(BOARD_FILE),)
$(error Config $(CONFIG) references board $(BOARD), but no board definition file found)
endif
export BOARD
export BOARD_FILE
include $(BOARD_FILE)
$(info % BOARD = $(BOARD))
@@ -385,7 +386,7 @@ define BUILTIN_DEF
endef
# Don't generate until modules have updated their command files
$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES)
$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(MODULE_MKFILES) $(BUILTIN_COMMAND_FILES)
@$(ECHO) "CMDS: $@"
$(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@
$(Q) $(ECHO) '#include <nuttx/config.h>' >> $@
+2 -1
View File
@@ -98,6 +98,7 @@
#
# CONFIG
# BOARD
# BOARD_FILE
# MODULE_WORK_DIR
# MODULE_OBJ
# MODULE_MK
@@ -117,7 +118,7 @@ $(info %% MODULE_MK = $(MODULE_MK))
#
# Get the board/toolchain config
#
include $(PX4_MK_DIR)/board_$(BOARD).mk
include $(BOARD_FILE)
#
# Get the module's config
+1
View File
@@ -65,6 +65,7 @@ export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
export MKFW = $(PX4_BASE)/Tools/px_mkfw.py
export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
export COPY = cp
export COPYDIR = cp -Rf
export REMOVE = rm -f
export RMDIR = rm -rf
export GENROMFS = genromfs
+7
View File
@@ -85,6 +85,13 @@ ifeq ($(ARCHCPUFLAGS),)
$(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3)
endif
# Set the board flags
#
ifeq ($(CONFIG_BOARD),)
$(error Board config does not define CONFIG_BOARD)
endif
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD)
# optimisation flags
#
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-2
View File
@@ -27,8 +27,6 @@ all: upload-$(METHOD)-$(BOARD)
upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER)
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER)
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
#
# JTAG firmware uploading with OpenOCD
+391
View File
@@ -0,0 +1,391 @@
/************************************************************************************
* configs/stm32f4discovery/include/board.h
* include/arch/board/board.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
#define __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32.h"
/************************************************************************************
* Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The PX4FMU uses a 24MHz crystal connected to the HSE.
*
* This is the canonical configuration:
* System Clock source : PLL (HSE)
* SYSCLK(Hz) : 168000000 Determined by PLL configuration
* HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
* AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
* APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
* APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
* HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL)
* PLLM : 24 (STM32_PLLCFG_PLLM)
* PLLN : 336 (STM32_PLLCFG_PLLN)
* PLLP : 2 (STM32_PLLCFG_PLLP)
* PLLQ : 7 (STM32_PLLCFG_PLLQ)
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
* Flash Latency(WS) : 5
* Prefetch Buffer : OFF
* Instruction cache : ON
* Data cache : ON
* Require 48MHz for USB OTG FS, : Enabled
* SDIO and RNG clock
*/
/* HSI - 16 MHz RC factory-trimmed
* LSI - 32 KHz RC
* HSE - On-board crystal frequency is 24MHz
* LSE - not installed
*/
#define STM32_BOARD_XTAL 24000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
//#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
* PLL source is HSE
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
* = (8,000,000 / 8) * 336
* = 336,000,000
* SYSCLK = PLL_VCO / PLLP
* = 336,000,000 / 2 = 168,000,000
* USB OTG FS, SDIO and RNG Clock
* = PLL_VCO / PLLQ
* = 48,000,000
*/
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
#define STM32_SYSCLK_FREQUENCY 168000000ul
/* AHB clock (HCLK) is SYSCLK (168MHz) */
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
* otherwise frequency is 2xAPBx.
* Note: TIM1,8 are on APB2, others on APB1
*/
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
/* High-resolution timer
*/
#define HRT_TIMER 1 /* use timer1 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
/* LED definitions ******************************************************************/
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
*/
/* LED index values for use with stm32_setled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_NLEDS 2
#define BOARD_LED_BLUE BOARD_LED1
#define BOARD_LED_RED BOARD_LED2
/* LED bits for use with stm32_setleds() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the
* px4fmu-v1. The following definitions describe how NuttX controls the LEDs:
*/
#define LED_STARTED 0 /* LED1 */
#define LED_HEAPALLOCATE 1 /* LED2 */
#define LED_IRQSENABLED 2 /* LED1 */
#define LED_STACKCREATED 3 /* LED1 + LED2 */
#define LED_INIRQ 4 /* LED1 */
#define LED_SIGNAL 5 /* LED2 */
#define LED_ASSERTION 6 /* LED1 + LED2 */
#define LED_PANIC 7 /* LED1 + LED2 */
/* Alternate function pin selections ************************************************/
/*
* UARTs.
*
* Note that UART5 has no optional pinout, so it is not listed here.
*/
#define GPIO_USART1_RX GPIO_USART1_RX_2
#define GPIO_USART1_TX GPIO_USART1_TX_2
#define GPIO_USART2_RX GPIO_USART2_RX_1
#define GPIO_USART2_TX GPIO_USART2_TX_1
#define GPIO_USART2_RTS GPIO_USART2_RTS_1
#define GPIO_USART2_CTS GPIO_USART2_CTS_1
#define GPIO_USART6_RX GPIO_USART6_RX_1
#define GPIO_USART6_TX GPIO_USART6_TX_1
/* UART DMA configuration for USART1/6 */
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
/*
* PWM
*
* Four PWM outputs can be configured on pins otherwise shared with
* USART2; two can take the flow control pins if they are not being used.
*
* Pins:
*
* CTS - PA0 - TIM2CH1
* RTS - PA1 - TIM2CH2
* TX - PA2 - TIM2CH3
* RX - PA3 - TIM2CH4
*
*/
#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
/*
* PPM
*
* PPM input is handled by the HRT timer.
*/
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
/*
* CAN
*
* CAN2 is routed to the expansion connector.
*/
#define GPIO_CAN2_RX GPIO_CAN2_RX_1
#define GPIO_CAN2_TX GPIO_CAN2_TX_1
/*
* I2C
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
/*
* I2C busses
*/
#define PX4_I2C_BUS_ESC 1
#define PX4_I2C_BUS_ONBOARD 2
#define PX4_I2C_BUS_EXPANSION 3
/*
* Devices on the onboard bus.
*
* Note that these are unshifted addresses.
*/
#define PX4_I2C_OBDEV_HMC5883 0x1e
#define PX4_I2C_OBDEV_MS5611 0x76
#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
#define PX4_I2C_OBDEV_PX4IO_BL 0x18
#define PX4_I2C_OBDEV_PX4IO 0x1a
/*
* SPI
*
* There are sensors on SPI1, and SPI3 is connected to the microSD slot.
*/
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2
/* SPI DMA configuration for SPI3 (microSD) */
#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1
#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2
/* XXX since we allocate the HP work stack from CCM RAM on normal system startup,
SPI1 will never run in DMA mode - so we can just give it a random config here.
What we really need to do is to make DMA configurable per channel, and always
disable it for SPI1. */
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2
/*
* Use these in place of the spi_dev_e enumeration to
* select a specific SPI device on SPI1
*/
#define PX4_SPIDEV_GYRO 1
#define PX4_SPIDEV_ACCEL 2
#define PX4_SPIDEV_MPU 3
/*
* Optional devices on IO's external port
*/
#define PX4_SPIDEV_ACCEL_MAG 2
/*
* Tone alarm output
*/
#define TONE_ALARM_TIMER 3 /* timer 3 */
#define TONE_ALARM_CHANNEL 3 /* channel 3 */
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
EXTERN void stm32_boardinitialize(void);
/************************************************************************************
* Name: stm32_ledinit, stm32_setled, and stm32_setleds
*
* Description:
* If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
* CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
* control the LEDs from user applications.
*
************************************************************************************/
#ifndef CONFIG_ARCH_LEDS
EXTERN void stm32_ledinit(void);
EXTERN void stm32_setled(int led, bool ledon);
EXTERN void stm32_setleds(uint8_t ledset);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H */
@@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* nsh_romfsetc.h
*
* This file is a stub for 'make export' purposes; the actual ROMFS
* must be supplied by the library client.
*/
extern unsigned char romfs_img[];
extern unsigned int romfs_img_len;
+179
View File
@@ -0,0 +1,179 @@
############################################################################
# configs/px4fmu-v1/nsh/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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 NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -O3
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# enable precise stack overflow tracking
INSTRUMENTATIONDEFINES = -finstrument-functions \
-ffixed-r10
# pull in *just* libm from the toolchain ... this is grody
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
EXTRA_LIBS += $(LIBM)
# use our linker script
LDSCRIPT = ld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# optimisation flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = -Wall \
-Wextra \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \
-Wframe-larger-than=1024 \
-Wpointer-arith \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
ARCHCWARNINGS = $(ARCHWARNINGS) \
-Wbad-function-cast \
-Wstrict-prototypes \
-Wold-style-declaration \
-Wmissing-parameter-type \
-Wmissing-prototypes \
-Wnested-externs \
-Wunsuffixed-float-constants
ARCHWARNINGSXX = $(ARCHWARNINGS) \
-Wno-psabi
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
+964
View File
@@ -0,0 +1,964 @@
#
# Automatically generated file; DO NOT EDIT.
# Nuttx/ Configuration
#
CONFIG_NUTTX_NEWCONFIG=y
#
# Build Setup
#
# CONFIG_EXPERIMENTAL is not set
# CONFIG_HOST_LINUX is not set
CONFIG_HOST_OSX=y
# CONFIG_HOST_WINDOWS is not set
# CONFIG_HOST_OTHER is not set
#
# Build Configuration
#
CONFIG_APPS_DIR="../apps"
# CONFIG_BUILD_2PASS is not set
#
# Binary Output Formats
#
# CONFIG_RRLOAD_BINARY is not set
# CONFIG_INTELHEX_BINARY is not set
# CONFIG_MOTOROLA_SREC is not set
CONFIG_RAW_BINARY=y
#
# Customize Header Files
#
# CONFIG_ARCH_STDBOOL_H is not set
CONFIG_ARCH_MATH_H=y
# CONFIG_ARCH_FLOAT_H is not set
# CONFIG_ARCH_STDARG_H is not set
#
# Debug Options
#
# CONFIG_DEBUG is not set
CONFIG_DEBUG_SYMBOLS=y
#
# System Type
#
# CONFIG_ARCH_8051 is not set
CONFIG_ARCH_ARM=y
# CONFIG_ARCH_AVR is not set
# CONFIG_ARCH_HC is not set
# CONFIG_ARCH_MIPS is not set
# CONFIG_ARCH_RGMP is not set
# CONFIG_ARCH_SH is not set
# CONFIG_ARCH_SIM is not set
# CONFIG_ARCH_X86 is not set
# CONFIG_ARCH_Z16 is not set
# CONFIG_ARCH_Z80 is not set
CONFIG_ARCH="arm"
#
# ARM Options
#
# CONFIG_ARCH_CHIP_C5471 is not set
# CONFIG_ARCH_CHIP_CALYPSO is not set
# CONFIG_ARCH_CHIP_DM320 is not set
# CONFIG_ARCH_CHIP_IMX is not set
# CONFIG_ARCH_CHIP_KINETIS is not set
# CONFIG_ARCH_CHIP_KL is not set
# CONFIG_ARCH_CHIP_LM is not set
# CONFIG_ARCH_CHIP_LPC17XX is not set
# CONFIG_ARCH_CHIP_LPC214X is not set
# CONFIG_ARCH_CHIP_LPC2378 is not set
# CONFIG_ARCH_CHIP_LPC31XX is not set
# CONFIG_ARCH_CHIP_LPC43XX is not set
# CONFIG_ARCH_CHIP_NUC1XX is not set
# CONFIG_ARCH_CHIP_SAM34 is not set
CONFIG_ARCH_CHIP_STM32=y
# CONFIG_ARCH_CHIP_STR71X is not set
CONFIG_ARCH_CORTEXM4=y
CONFIG_ARCH_FAMILY="armv7-m"
CONFIG_ARCH_CHIP="stm32"
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARCH_HAVE_CMNVECTOR=y
CONFIG_ARMV7M_CMNVECTOR=y
CONFIG_ARCH_HAVE_FPU=y
CONFIG_ARCH_FPU=y
CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARMV7M_MPU is not set
#
# ARMV7M Configuration Options
#
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
CONFIG_ARMV7M_STACKCHECK=y
CONFIG_SERIAL_TERMIOS=y
#
# STM32 Configuration Options
#
# CONFIG_ARCH_CHIP_STM32L151C6 is not set
# CONFIG_ARCH_CHIP_STM32L151C8 is not set
# CONFIG_ARCH_CHIP_STM32L151CB is not set
# CONFIG_ARCH_CHIP_STM32L151R6 is not set
# CONFIG_ARCH_CHIP_STM32L151R8 is not set
# CONFIG_ARCH_CHIP_STM32L151RB is not set
# CONFIG_ARCH_CHIP_STM32L151V6 is not set
# CONFIG_ARCH_CHIP_STM32L151V8 is not set
# CONFIG_ARCH_CHIP_STM32L151VB is not set
# CONFIG_ARCH_CHIP_STM32L152C6 is not set
# CONFIG_ARCH_CHIP_STM32L152C8 is not set
# CONFIG_ARCH_CHIP_STM32L152CB is not set
# CONFIG_ARCH_CHIP_STM32L152R6 is not set
# CONFIG_ARCH_CHIP_STM32L152R8 is not set
# CONFIG_ARCH_CHIP_STM32L152RB is not set
# CONFIG_ARCH_CHIP_STM32L152V6 is not set
# CONFIG_ARCH_CHIP_STM32L152V8 is not set
# CONFIG_ARCH_CHIP_STM32L152VB is not set
# CONFIG_ARCH_CHIP_STM32F100C8 is not set
# CONFIG_ARCH_CHIP_STM32F100CB is not set
# CONFIG_ARCH_CHIP_STM32F100R8 is not set
# CONFIG_ARCH_CHIP_STM32F100RB is not set
# CONFIG_ARCH_CHIP_STM32F100RC is not set
# CONFIG_ARCH_CHIP_STM32F100RD is not set
# CONFIG_ARCH_CHIP_STM32F100RE is not set
# CONFIG_ARCH_CHIP_STM32F100V8 is not set
# CONFIG_ARCH_CHIP_STM32F100VB is not set
# CONFIG_ARCH_CHIP_STM32F100VC is not set
# CONFIG_ARCH_CHIP_STM32F100VD is not set
# CONFIG_ARCH_CHIP_STM32F100VE is not set
# CONFIG_ARCH_CHIP_STM32F103C4 is not set
# CONFIG_ARCH_CHIP_STM32F103C8 is not set
# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
# CONFIG_ARCH_CHIP_STM32F107VC is not set
# CONFIG_ARCH_CHIP_STM32F207IG is not set
# CONFIG_ARCH_CHIP_STM32F302CB is not set
# CONFIG_ARCH_CHIP_STM32F302CC is not set
# CONFIG_ARCH_CHIP_STM32F302RB is not set
# CONFIG_ARCH_CHIP_STM32F302RC is not set
# CONFIG_ARCH_CHIP_STM32F302VB is not set
# CONFIG_ARCH_CHIP_STM32F302VC is not set
# CONFIG_ARCH_CHIP_STM32F303CB is not set
# CONFIG_ARCH_CHIP_STM32F303CC is not set
# CONFIG_ARCH_CHIP_STM32F303RB is not set
# CONFIG_ARCH_CHIP_STM32F303RC is not set
# CONFIG_ARCH_CHIP_STM32F303VB is not set
# CONFIG_ARCH_CHIP_STM32F303VC is not set
CONFIG_ARCH_CHIP_STM32F405RG=y
# CONFIG_ARCH_CHIP_STM32F405VG is not set
# CONFIG_ARCH_CHIP_STM32F405ZG is not set
# CONFIG_ARCH_CHIP_STM32F407VE is not set
# CONFIG_ARCH_CHIP_STM32F407VG is not set
# CONFIG_ARCH_CHIP_STM32F407ZE is not set
# CONFIG_ARCH_CHIP_STM32F407ZG is not set
# CONFIG_ARCH_CHIP_STM32F407IE is not set
# CONFIG_ARCH_CHIP_STM32F407IG is not set
# CONFIG_ARCH_CHIP_STM32F427V is not set
# CONFIG_ARCH_CHIP_STM32F427Z is not set
# CONFIG_ARCH_CHIP_STM32F427I is not set
# CONFIG_STM32_STM32L15XX is not set
# CONFIG_STM32_ENERGYLITE is not set
# CONFIG_STM32_STM32F10XX is not set
# CONFIG_STM32_VALUELINE is not set
# CONFIG_STM32_CONNECTIVITYLINE is not set
# CONFIG_STM32_PERFORMANCELINE is not set
# CONFIG_STM32_HIGHDENSITY is not set
# CONFIG_STM32_MEDIUMDENSITY is not set
# CONFIG_STM32_LOWDENSITY is not set
# CONFIG_STM32_STM32F20XX is not set
# CONFIG_STM32_STM32F30XX is not set
CONFIG_STM32_STM32F40XX=y
# CONFIG_STM32_DFU is not set
#
# STM32 Peripheral Support
#
CONFIG_STM32_ADC1=y
# CONFIG_STM32_ADC2 is not set
# CONFIG_STM32_ADC3 is not set
CONFIG_STM32_BKPSRAM=y
# CONFIG_STM32_CAN1 is not set
# CONFIG_STM32_CAN2 is not set
CONFIG_STM32_CCMDATARAM=y
# CONFIG_STM32_CRC is not set
# CONFIG_STM32_CRYP is not set
CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=y
# CONFIG_STM32_DAC1 is not set
# CONFIG_STM32_DAC2 is not set
# CONFIG_STM32_DCMI is not set
# CONFIG_STM32_ETHMAC is not set
# CONFIG_STM32_FSMC is not set
# CONFIG_STM32_HASH is not set
CONFIG_STM32_I2C1=y
CONFIG_STM32_I2C2=y
CONFIG_STM32_I2C3=y
CONFIG_STM32_OTGFS=y
# CONFIG_STM32_OTGHS is not set
CONFIG_STM32_PWR=y
# CONFIG_STM32_RNG is not set
# CONFIG_STM32_SDIO is not set
CONFIG_STM32_SPI1=y
# CONFIG_STM32_SPI2 is not set
CONFIG_STM32_SPI3=y
CONFIG_STM32_SYSCFG=y
# CONFIG_STM32_TIM1 is not set
# CONFIG_STM32_TIM2 is not set
# CONFIG_STM32_TIM3 is not set
CONFIG_STM32_TIM4=y
CONFIG_STM32_TIM5=y
CONFIG_STM32_TIM6=y
CONFIG_STM32_TIM7=y
# CONFIG_STM32_TIM8 is not set
CONFIG_STM32_TIM9=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
CONFIG_STM32_TIM12=y
CONFIG_STM32_TIM13=y
CONFIG_STM32_TIM14=y
CONFIG_STM32_USART1=y
CONFIG_STM32_USART2=y
# CONFIG_STM32_USART3 is not set
# CONFIG_STM32_UART4 is not set
CONFIG_STM32_UART5=y
CONFIG_STM32_USART6=y
# CONFIG_STM32_IWDG is not set
CONFIG_STM32_WWDG=y
CONFIG_STM32_ADC=y
CONFIG_STM32_SPI=y
CONFIG_STM32_I2C=y
#
# Alternate Pin Mapping
#
CONFIG_STM32_FLASH_PREFETCH=y
# CONFIG_STM32_JTAG_DISABLE is not set
CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
# CONFIG_STM32_JTAG_SW_ENABLE is not set
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
# CONFIG_STM32_FORCEPOWER is not set
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
# CONFIG_STM32_CCMEXCLUDE is not set
CONFIG_STM32_DMACAPABLE=y
# CONFIG_STM32_TIM4_PWM is not set
# CONFIG_STM32_TIM5_PWM is not set
# CONFIG_STM32_TIM9_PWM is not set
# CONFIG_STM32_TIM10_PWM is not set
# CONFIG_STM32_TIM11_PWM is not set
# CONFIG_STM32_TIM12_PWM is not set
# CONFIG_STM32_TIM13_PWM is not set
# CONFIG_STM32_TIM14_PWM is not set
# CONFIG_STM32_TIM4_ADC is not set
# CONFIG_STM32_TIM5_ADC is not set
CONFIG_STM32_USART=y
#
# U[S]ART Configuration
#
# CONFIG_USART1_RS485 is not set
# CONFIG_USART1_RXDMA is not set
# CONFIG_USART2_RS485 is not set
CONFIG_USART2_RXDMA=y
# CONFIG_USART3_RXDMA is not set
# CONFIG_UART4_RXDMA is not set
# CONFIG_UART5_RS485 is not set
CONFIG_UART5_RXDMA=y
# CONFIG_USART6_RS485 is not set
CONFIG_USART6_RXDMA=y
# CONFIG_USART7_RXDMA is not set
# CONFIG_USART8_RXDMA is not set
CONFIG_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32_USART_SINGLEWIRE=y
#
# SPI Configuration
#
# CONFIG_STM32_SPI_INTERRUPTS is not set
# CONFIG_STM32_SPI_DMA is not set
#
# I2C Configuration
#
# CONFIG_STM32_I2C_DYNTIMEO is not set
CONFIG_STM32_I2CTIMEOSEC=0
CONFIG_STM32_I2CTIMEOMS=10
CONFIG_STM32_I2CTIMEOTICKS=500
# CONFIG_STM32_I2C_DUTY16_9 is not set
#
# USB Host Configuration
#
#
# USB Device Configuration
#
#
# External Memory Configuration
#
#
# Architecture Options
#
# CONFIG_ARCH_NOINTC is not set
# CONFIG_ARCH_VECNOTIRQ is not set
CONFIG_ARCH_DMA=y
CONFIG_ARCH_IRQPRIO=y
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
CONFIG_ARCH_HAVE_VFORK=y
CONFIG_ARCH_STACKDUMP=y
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_HAVE_RAMFUNCS is not set
CONFIG_ARCH_HAVE_RAMVECTORS=y
# CONFIG_ARCH_RAMVECTORS is not set
#
# Board Settings
#
CONFIG_BOARD_LOOPSPERMSEC=16717
# CONFIG_ARCH_CALIBRATION is not set
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=196608
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
CONFIG_ARCH_INTERRUPTSTACK=2048
#
# Boot options
#
# CONFIG_BOOT_RUNFROMEXTSRAM is not set
CONFIG_BOOT_RUNFROMFLASH=y
# CONFIG_BOOT_RUNFROMISRAM is not set
# CONFIG_BOOT_RUNFROMSDRAM is not set
# CONFIG_BOOT_COPYTORAM is not set
#
# Board Selection
#
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD=""
#
# Common Board Options
#
CONFIG_NSH_MMCSDMINOR=0
CONFIG_NSH_MMCSDSLOTNO=0
CONFIG_NSH_MMCSDSPIPORTNO=3
#
# Board-Specific Options
#
#
# RTOS Features
#
# CONFIG_BOARD_INITIALIZE is not set
CONFIG_MSEC_PER_TICK=1
CONFIG_RR_INTERVAL=0
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_TASK_NAME_SIZE=24
# CONFIG_SCHED_HAVE_PARENT is not set
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=1970
CONFIG_START_MONTH=1
CONFIG_START_DAY=1
# CONFIG_DEV_CONSOLE is not set
# CONFIG_MUTEX_TYPES is not set
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_NNESTPRIO=8
# CONFIG_FDCLONE_DISABLE is not set
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WAITPID=y
# CONFIG_SCHED_STARTHOOK is not set
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_ATEXIT_MAX=1
# CONFIG_SCHED_ONEXIT is not set
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_DISABLE_OS_API=y
# CONFIG_DISABLE_CLOCK is not set
# CONFIG_DISABLE_POSIX_TIMERS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_DISABLE_SIGNALS is not set
# CONFIG_DISABLE_MQUEUE is not set
# CONFIG_DISABLE_ENVIRON is not set
#
# Signal Numbers
#
CONFIG_SIG_SIGUSR1=1
CONFIG_SIG_SIGUSR2=2
CONFIG_SIG_SIGALARM=3
CONFIG_SIG_SIGCONDTIMEDOUT=16
CONFIG_SIG_SIGWORK=4
#
# Sizes of configurable things (0 disables)
#
CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
CONFIG_NFILE_DESCRIPTORS=32
CONFIG_NFILE_STREAMS=25
CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
CONFIG_MAX_WDOGPARMS=2
CONFIG_PREALLOC_WDOGS=50
CONFIG_PREALLOC_TIMERS=50
#
# Stack and heap information
#
CONFIG_IDLETHREAD_STACKSIZE=6000
CONFIG_USERMAIN_STACKSIZE=4096
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=2048
#
# Device Drivers
#
# CONFIG_DISABLE_POLL is not set
CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set
# CONFIG_RAMDISK is not set
# CONFIG_CAN is not set
# CONFIG_PWM is not set
CONFIG_I2C=y
# CONFIG_I2C_SLAVE is not set
CONFIG_I2C_TRANSFER=y
# CONFIG_I2C_WRITEREAD is not set
# CONFIG_I2C_POLLED is not set
# CONFIG_I2C_TRACE is not set
CONFIG_ARCH_HAVE_I2CRESET=y
CONFIG_I2C_RESET=y
CONFIG_SPI=y
# CONFIG_SPI_OWNBUS is not set
CONFIG_SPI_EXCHANGE=y
# CONFIG_SPI_CMDDATA is not set
# CONFIG_RTC is not set
CONFIG_WATCHDOG=y
# CONFIG_ANALOG is not set
# CONFIG_AUDIO_DEVICES is not set
# CONFIG_BCH is not set
# CONFIG_INPUT is not set
# CONFIG_LCD is not set
CONFIG_MMCSD=y
CONFIG_MMCSD_NSLOTS=1
# CONFIG_MMCSD_READONLY is not set
# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_HAVECARDDETECT is not set
CONFIG_MMCSD_SPI=y
CONFIG_MMCSD_SPICLOCK=24000000
# CONFIG_MMCSD_SDIO is not set
# CONFIG_MTD is not set
CONFIG_PIPES=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_16550_UART is not set
CONFIG_ARCH_HAVE_UART5=y
CONFIG_ARCH_HAVE_USART1=y
CONFIG_ARCH_HAVE_USART2=y
CONFIG_ARCH_HAVE_USART6=y
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
CONFIG_SERIAL_NPOLLWAITERS=2
# CONFIG_USART1_SERIAL_CONSOLE is not set
# CONFIG_USART2_SERIAL_CONSOLE is not set
# CONFIG_UART5_SERIAL_CONSOLE is not set
# CONFIG_USART6_SERIAL_CONSOLE is not set
CONFIG_NO_SERIAL_CONSOLE=y
#
# USART1 Configuration
#
CONFIG_USART1_RXBUFSIZE=512
CONFIG_USART1_TXBUFSIZE=512
CONFIG_USART1_BAUD=57600
CONFIG_USART1_BITS=8
CONFIG_USART1_PARITY=0
CONFIG_USART1_2STOP=0
# CONFIG_USART1_IFLOWCONTROL is not set
# CONFIG_USART1_OFLOWCONTROL is not set
#
# USART2 Configuration
#
CONFIG_USART2_RXBUFSIZE=512
CONFIG_USART2_TXBUFSIZE=512
CONFIG_USART2_BAUD=57600
CONFIG_USART2_BITS=8
CONFIG_USART2_PARITY=0
CONFIG_USART2_2STOP=0
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
#
# UART5 Configuration
#
CONFIG_UART5_RXBUFSIZE=32
CONFIG_UART5_TXBUFSIZE=32
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
CONFIG_UART5_2STOP=0
# CONFIG_UART5_IFLOWCONTROL is not set
# CONFIG_UART5_OFLOWCONTROL is not set
#
# USART6 Configuration
#
CONFIG_USART6_RXBUFSIZE=512
CONFIG_USART6_TXBUFSIZE=512
CONFIG_USART6_BAUD=57600
CONFIG_USART6_BITS=8
CONFIG_USART6_PARITY=0
CONFIG_USART6_2STOP=0
# CONFIG_USART6_IFLOWCONTROL is not set
# CONFIG_USART6_OFLOWCONTROL is not set
CONFIG_SERIAL_IFLOWCONTROL=y
CONFIG_SERIAL_OFLOWCONTROL=y
CONFIG_USBDEV=y
#
# USB Device Controller Driver Options
#
# CONFIG_USBDEV_ISOCHRONOUS is not set
# CONFIG_USBDEV_DUALSPEED is not set
# CONFIG_USBDEV_SELFPOWERED is not set
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
# CONFIG_USBDEV_REMOTEWAKEUP is not set
# CONFIG_USBDEV_DMA is not set
# CONFIG_USBDEV_TRACE is not set
#
# USB Device Class Driver Options
#
# CONFIG_USBDEV_COMPOSITE is not set
# CONFIG_PL2303 is not set
CONFIG_CDCACM=y
CONFIG_CDCACM_CONSOLE=y
CONFIG_CDCACM_EP0MAXPACKET=64
CONFIG_CDCACM_EPINTIN=1
CONFIG_CDCACM_EPINTIN_FSSIZE=64
CONFIG_CDCACM_EPINTIN_HSSIZE=64
CONFIG_CDCACM_EPBULKOUT=3
CONFIG_CDCACM_EPBULKOUT_FSSIZE=64
CONFIG_CDCACM_EPBULKOUT_HSSIZE=512
CONFIG_CDCACM_EPBULKIN=2
CONFIG_CDCACM_EPBULKIN_FSSIZE=64
CONFIG_CDCACM_EPBULKIN_HSSIZE=512
CONFIG_CDCACM_NWRREQS=4
CONFIG_CDCACM_NRDREQS=4
CONFIG_CDCACM_BULKIN_REQLEN=96
CONFIG_CDCACM_RXBUFSIZE=256
CONFIG_CDCACM_TXBUFSIZE=256
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_PRODUCTID=0x0010
CONFIG_CDCACM_VENDORSTR="3D Robotics"
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.x"
# CONFIG_USBMSC is not set
# CONFIG_USBHOST is not set
# CONFIG_WIRELESS is not set
#
# System Logging Device Options
#
#
# System Logging
#
# CONFIG_RAMLOG is not set
#
# Networking Support
#
# CONFIG_NET is not set
#
# File Systems
#
#
# File system configuration
#
# CONFIG_DISABLE_MOUNTPOINT is not set
# CONFIG_FS_RAMMAP is not set
CONFIG_FS_FAT=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=32
CONFIG_FS_FATTIME=y
# CONFIG_FAT_DMAMEMORY is not set
CONFIG_FS_NXFFS=y
CONFIG_NXFFS_PREALLOCATED=y
CONFIG_NXFFS_ERASEDSTATE=0xff
CONFIG_NXFFS_PACKTHRESHOLD=32
CONFIG_NXFFS_MAXNAMLEN=32
CONFIG_NXFFS_TAILTHRESHOLD=2048
CONFIG_FS_ROMFS=y
# CONFIG_FS_SMARTFS is not set
CONFIG_FS_BINFS=y
#
# System Logging
#
# CONFIG_SYSLOG_ENABLE is not set
CONFIG_SYSLOG=y
CONFIG_SYSLOG_CHAR=y
CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
#
# Graphics Support
#
# CONFIG_NX is not set
#
# Memory Management
#
# CONFIG_MM_MULTIHEAP is not set
# CONFIG_MM_SMALL is not set
CONFIG_MM_REGIONS=2
CONFIG_GRAN=y
CONFIG_GRAN_SINGLE=y
CONFIG_GRAN_INTR=y
#
# Audio Support
#
# CONFIG_AUDIO is not set
#
# Binary Formats
#
# CONFIG_BINFMT_DISABLE is not set
# CONFIG_BINFMT_EXEPATH is not set
# CONFIG_NXFLAT is not set
# CONFIG_ELF is not set
CONFIG_BUILTIN=y
# CONFIG_PIC is not set
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
#
# Library Routines
#
#
# Standard C Library Options
#
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STDIO_LINEBUFFER=y
CONFIG_NUNGET_CHARS=2
CONFIG_LIB_HOMEDIR="/"
# CONFIG_NOPRINTF_FIELDWIDTH is not set
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIB_RAND_ORDER=1
# CONFIG_EOL_IS_CR is not set
# CONFIG_EOL_IS_LF is not set
# CONFIG_EOL_IS_BOTH_CRLF is not set
CONFIG_EOL_IS_EITHER_CRLF=y
# CONFIG_LIBC_EXECFUNCS is not set
CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
CONFIG_LIBC_STRERROR=y
# CONFIG_LIBC_STRERROR_SHORT is not set
# CONFIG_LIBC_PERROR_STDOUT is not set
CONFIG_ARCH_LOWPUTC=y
CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_ARCH_ROMGETC is not set
CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
CONFIG_ARCH_MEMCPY=y
# CONFIG_ARCH_MEMCMP is not set
# CONFIG_ARCH_MEMMOVE is not set
# CONFIG_ARCH_MEMSET is not set
# CONFIG_MEMSET_OPTSPEED is not set
# CONFIG_ARCH_STRCHR is not set
# CONFIG_ARCH_STRCMP is not set
# CONFIG_ARCH_STRCPY is not set
# CONFIG_ARCH_STRNCPY is not set
# CONFIG_ARCH_STRLEN is not set
# CONFIG_ARCH_STRNLEN is not set
# CONFIG_ARCH_BZERO is not set
#
# Non-standard Library Support
#
CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
CONFIG_SCHED_WORKSTACKSIZE=2048
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
CONFIG_SCHED_LPWORKSTACKSIZE=2048
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
#
# Basic CXX Support
#
# CONFIG_C99_BOOL8 is not set
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
# CONFIG_CXX_NEWLONG is not set
#
# uClibc++ Standard C++ Library
#
# CONFIG_UCLIBCXX is not set
#
# Application Configuration
#
#
# Built-In Applications
#
CONFIG_BUILTIN_PROXY_STACKSIZE=1024
#
# Examples
#
# CONFIG_EXAMPLES_BUTTONS is not set
# CONFIG_EXAMPLES_CAN is not set
CONFIG_EXAMPLES_CDCACM=y
# CONFIG_EXAMPLES_COMPOSITE is not set
# CONFIG_EXAMPLES_CXXTEST is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
# CONFIG_EXAMPLES_FTPC is not set
# CONFIG_EXAMPLES_FTPD is not set
# CONFIG_EXAMPLES_HELLO is not set
# CONFIG_EXAMPLES_HELLOXX is not set
# CONFIG_EXAMPLES_JSON is not set
# CONFIG_EXAMPLES_HIDKBD is not set
# CONFIG_EXAMPLES_KEYPADTEST is not set
# CONFIG_EXAMPLES_IGMP is not set
# CONFIG_EXAMPLES_LCDRW is not set
# CONFIG_EXAMPLES_MM is not set
# CONFIG_EXAMPLES_MODBUS is not set
CONFIG_EXAMPLES_MOUNT=y
# CONFIG_EXAMPLES_NRF24L01TERM is not set
CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_NULL is not set
# CONFIG_EXAMPLES_NX is not set
# CONFIG_EXAMPLES_NXCONSOLE is not set
# CONFIG_EXAMPLES_NXFFS is not set
# CONFIG_EXAMPLES_NXFLAT is not set
# CONFIG_EXAMPLES_NXHELLO is not set
# CONFIG_EXAMPLES_NXIMAGE is not set
# CONFIG_EXAMPLES_NXLINES is not set
# CONFIG_EXAMPLES_NXTEXT is not set
# CONFIG_EXAMPLES_OSTEST is not set
# CONFIG_EXAMPLES_PASHELLO is not set
# CONFIG_EXAMPLES_PIPE is not set
# CONFIG_EXAMPLES_POSIXSPAWN is not set
# CONFIG_EXAMPLES_QENCODER is not set
# CONFIG_EXAMPLES_RGMP is not set
# CONFIG_EXAMPLES_ROMFS is not set
# CONFIG_EXAMPLES_SENDMAIL is not set
# CONFIG_EXAMPLES_SERLOOP is not set
# CONFIG_EXAMPLES_SLCD is not set
# CONFIG_EXAMPLES_SMART_TEST is not set
# CONFIG_EXAMPLES_SMART is not set
# CONFIG_EXAMPLES_TCPECHO is not set
# CONFIG_EXAMPLES_TELNETD is not set
# CONFIG_EXAMPLES_THTTPD is not set
# CONFIG_EXAMPLES_TIFF is not set
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
# CONFIG_EXAMPLES_UDP is not set
# CONFIG_EXAMPLES_UIP is not set
# CONFIG_EXAMPLES_USBSERIAL is not set
# CONFIG_EXAMPLES_USBMSC is not set
# CONFIG_EXAMPLES_USBTERM is not set
# CONFIG_EXAMPLES_WATCHDOG is not set
#
# Graphics Support
#
# CONFIG_TIFF is not set
#
# Interpreters
#
# CONFIG_INTERPRETERS_FICL is not set
# CONFIG_INTERPRETERS_PCODE is not set
#
# Network Utilities
#
#
# Networking Utilities
#
# CONFIG_NETUTILS_CODECS is not set
# CONFIG_NETUTILS_DHCPC is not set
# CONFIG_NETUTILS_DHCPD is not set
# CONFIG_NETUTILS_FTPC is not set
# CONFIG_NETUTILS_FTPD is not set
# CONFIG_NETUTILS_JSON is not set
# CONFIG_NETUTILS_RESOLV is not set
# CONFIG_NETUTILS_SMTP is not set
# CONFIG_NETUTILS_TELNETD is not set
# CONFIG_NETUTILS_TFTPC is not set
# CONFIG_NETUTILS_THTTPD is not set
# CONFIG_NETUTILS_UIPLIB is not set
# CONFIG_NETUTILS_WEBCLIENT is not set
#
# FreeModBus
#
# CONFIG_MODBUS is not set
#
# NSH Library
#
CONFIG_NSH_LIBRARY=y
CONFIG_NSH_BUILTIN_APPS=y
#
# Disable Individual commands
#
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DD is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_HEXDUMP is not set
# CONFIG_NSH_DISABLE_IFCONFIG is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOSETUP is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MB is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MKFIFO is not set
# CONFIG_NSH_DISABLE_MKRD is not set
# CONFIG_NSH_DISABLE_MH is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MW is not set
# CONFIG_NSH_DISABLE_NSFMOUNT is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PING is not set
# CONFIG_NSH_DISABLE_PUT is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SH is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
# CONFIG_NSH_DISABLE_WGET is not set
# CONFIG_NSH_DISABLE_XD is not set
#
# Configure Command Options
#
# CONFIG_NSH_CMDOPT_DF_H is not set
CONFIG_NSH_CODECS_BUFSIZE=128
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_STRERROR=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=12
CONFIG_NSH_NESTDEPTH=8
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLEBG is not set
CONFIG_NSH_ROMFSETC=y
# CONFIG_NSH_ROMFSRC is not set
CONFIG_NSH_ROMFSMOUNTPT="/etc"
CONFIG_NSH_INITSCRIPT="init.d/rcS"
CONFIG_NSH_ROMFSDEVNO=0
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_FATDEVNO=1
CONFIG_NSH_FATSECTSIZE=512
CONFIG_NSH_FATNSECTORS=1024
CONFIG_NSH_FATMOUNTPT="/tmp"
CONFIG_NSH_CONSOLE=y
# CONFIG_NSH_USBCONSOLE is not set
#
# USB Trace Support
#
# CONFIG_NSH_CONDEV is not set
CONFIG_NSH_ARCHINIT=y
#
# NxWidgets/NxWM
#
#
# System NSH Add-Ons
#
#
# Custom Free Memory Command
#
# CONFIG_SYSTEM_FREE is not set
#
# I2C tool
#
# CONFIG_SYSTEM_I2CTOOL is not set
#
# FLASH Program Installation
#
# CONFIG_SYSTEM_INSTALL is not set
#
# FLASH Erase-all Command
#
#
# readline()
#
CONFIG_SYSTEM_READLINE=y
CONFIG_READLINE_ECHO=y
#
# Power Off
#
# CONFIG_SYSTEM_POWEROFF is not set
#
# RAMTRON
#
# CONFIG_SYSTEM_RAMTRON is not set
#
# SD Card
#
# CONFIG_SYSTEM_SDCARD is not set
#
# Sysinfo
#
CONFIG_SYSTEM_SYSINFO=y
#
# USB Monitor
#
+75
View File
@@ -0,0 +1,75 @@
#!/bin/bash
# configs/px4fmu-v1/usbnsh/setenv.sh
#
# Copyright (C) 2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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 NuttX 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.
#
if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
WD=`pwd`
if [ ! -x "setenv.sh" ]; then
echo "This script must be executed from the top-level NuttX build directory"
exit 1
fi
if [ -z "${PATH_ORIG}" ]; then
export PATH_ORIG="${PATH}"
fi
# This is the Cygwin path to the location where I installed the RIDE
# toolchain under windows. You will also have to edit this if you install
# the RIDE toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
# This is the Cygwin path to the location where I installed the CodeSourcery
# toolchain under windows. You will also have to edit this if you install
# the CodeSourcery toolchain in any other location
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
# These are the Cygwin paths to the locations where I installed the Atollic
# toolchain under windows. You will also have to edit this if you install
# the Atollic toolchain in any other location. /usr/bin is added before
# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
# at those locations as well.
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
# This is the Cygwin path to the location where I build the buildroot
# toolchain.
#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
# Add the path to the toolchain to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
+149
View File
@@ -0,0 +1,149 @@
/****************************************************************************
* configs/px4fmu-v1/scripts/ld.script
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX 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.
*
****************************************************************************/
/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and
* 192Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
* 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*
* The first 0x4000 of flash is reserved for the bootloader.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
/*
* This is a hack to make the newlib libm __errno() call
* use the NuttX get_errno_ptr() function.
*/
__errno = get_errno_ptr;
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
/*
* Construction data for parameters.
*/
__param ALIGN(4): {
__param_start = ABSOLUTE(.);
KEEP(*(__param*))
__param_end = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
+84
View File
@@ -0,0 +1,84 @@
############################################################################
# configs/px4fmu-v1/src/Makefile
#
# Copyright (C) 2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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 NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
-include $(TOPDIR)/Make.defs
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = empty.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(WINTOOL),y)
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
else
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
endif
all: libboard$(LIBEXT)
$(AOBJS): %$(OBJEXT): %.S
$(call ASSEMBLE, $<, $@)
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
libboard$(LIBEXT): $(OBJS)
$(call ARCHIVE, $@, $(OBJS))
.depend: Makefile $(SRCS)
$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
$(Q) touch $@
depend: .depend
clean:
$(call DELFILE, libboard$(LIBEXT))
$(call CLEAN)
distclean: clean
$(call DELFILE, Make.dep)
$(call DELFILE, .depend)
-include Make.dep
+4
View File
@@ -0,0 +1,4 @@
/*
* There are no source files here, but libboard.a can't be empty, so
* we have this empty source file to keep it company.
*/
+1
View File
@@ -0,0 +1 @@
This directory contains header files unique to the PX4IO board.
+168
View File
@@ -0,0 +1,168 @@
/************************************************************************************
* configs/px4io/include/board.h
* include/arch/board/board.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_BOARD_BOARD_H
#define __ARCH_BOARD_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
# include <stdbool.h>
#endif
#include <stm32_rcc.h>
#include <stm32_sdio.h>
#include <stm32.h>
/************************************************************************************
* Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* On-board crystal frequency is 24MHz (HSE) */
#define STM32_BOARD_XTAL 24000000ul
/* Use the HSE output as the system clock */
#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE
#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE
#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL
/* AHB clock (HCLK) is SYSCLK (24MHz) */
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB2 clock (PCLK2) is HCLK (24MHz) */
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */
/* APB2 timer 1 will receive PCLK2. */
#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
/* APB1 clock (PCLK1) is HCLK (24MHz) */
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY)
/* All timers run off PCLK */
#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY)
/*
* Some of the USART pins are not available; override the GPIO
* definitions with an invalid pin configuration.
*/
#undef GPIO_USART2_CTS
#define GPIO_USART2_CTS 0xffffffff
#undef GPIO_USART2_RTS
#define GPIO_USART2_RTS 0xffffffff
#undef GPIO_USART2_CK
#define GPIO_USART2_CK 0xffffffff
#undef GPIO_USART3_TX
#define GPIO_USART3_TX 0xffffffff
#undef GPIO_USART3_CK
#define GPIO_USART3_CK 0xffffffff
#undef GPIO_USART3_CTS
#define GPIO_USART3_CTS 0xffffffff
#undef GPIO_USART3_RTS
#define GPIO_USART3_RTS 0xffffffff
/*
* High-resolution timer
*/
#define HRT_TIMER 1 /* use timer1 for the HRT */
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
/*
* PPM
*
* PPM input is handled by the HRT timer.
*
* Pin is PA8, timer 1, channel 1
*/
#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN GPIO_TIM1_CH1IN
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
EXTERN void stm32_boardinitialize(void);
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_BOARD_BOARD_H */
+166
View File
@@ -0,0 +1,166 @@
############################################################################
# configs/px4io-v1/nsh/Make.defs
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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 NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -O3
ARCHCPUFLAGS = -mcpu=cortex-m3 \
-mthumb \
-march=armv7-m
# use our linker script
LDSCRIPT = ld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# optimisation flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = -Wall \
-Wextra \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \
-Wframe-larger-than=1024 \
-Wpointer-arith \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
ARCHCWARNINGS = $(ARCHWARNINGS) \
-Wbad-function-cast \
-Wstrict-prototypes \
-Wold-style-declaration \
-Wmissing-parameter-type \
-Wmissing-prototypes \
-Wnested-externs \
-Wunsuffixed-float-constants
ARCHWARNINGSXX = $(ARCHWARNINGS)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
+32
View File
@@ -0,0 +1,32 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
+537
View File
@@ -0,0 +1,537 @@
############################################################################
# configs/px4io-v1/nsh/defconfig
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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 NuttX 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.
#
############################################################################
#
# architecture selection
#
# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
# processor architecture.
# CONFIG_ARCH_family - for use in C code. This identifies the
# particular chip family that the architecture is implemented
# in.
# CONFIG_ARCH_architecture - for use in C code. This identifies the
# specific architecture within the chip family.
# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
# CONFIG_ARCH_CHIP_name - For use in C code
# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
# the board that supports the particular chip or SoC.
# CONFIG_ARCH_BOARD_name - for use in C code
# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
# stack in bytes. If not defined, the user task stacks will be
# used during interrupt handling.
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
#
CONFIG_ARCH="arm"
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F100C8=y
#
# Board Selection
#
CONFIG_ARCH_BOARD_PX4IO_V1=y
# CONFIG_ARCH_BOARD_CUSTOM is not set
CONFIG_ARCH_BOARD="px4io-v1"
CONFIG_BOARD_LOOPSPERMSEC=2000
CONFIG_DRAM_SIZE=0x00002000
CONFIG_DRAM_START=0x20000000
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=y
CONFIG_ARCH_MATH_H=y
CONFIG_ARMV7M_CMNVECTOR=y
# CONFIG_ARMV7M_STACKCHECK is not set
#
# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
#
# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG
#
# JTAG Enable options:
#
# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
# but without JNTRST.
# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
#
CONFIG_STM32_DFU=n
CONFIG_STM32_JTAG_FULL_ENABLE=y
CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
# Individual subsystems can be enabled:
#
# AHB:
CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=n
CONFIG_STM32_CRC=n
# APB1:
# Timers 2,3 and 4 are owned by the PWM driver
CONFIG_STM32_TIM2=n
CONFIG_STM32_TIM3=n
CONFIG_STM32_TIM4=n
CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_USART2=y
CONFIG_STM32_USART3=y
CONFIG_STM32_I2C1=y
CONFIG_STM32_I2C2=n
CONFIG_STM32_BKP=n
CONFIG_STM32_PWR=n
CONFIG_STM32_DAC=n
# APB2:
# We use our own ADC driver, but leave this on for clocking purposes.
CONFIG_STM32_ADC1=y
CONFIG_STM32_ADC2=n
# TIM1 is owned by the HRT
CONFIG_STM32_TIM1=n
CONFIG_STM32_SPI1=n
CONFIG_STM32_TIM8=n
CONFIG_STM32_USART1=y
CONFIG_STM32_ADC3=n
#
# STM32F100 specific serial device driver settings
#
# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
# console and ttys0 (default is the USART1).
# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
# This specific the size of the receive buffer
# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before
# being sent. This specific the size of the transmit buffer
# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be
# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8.
# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
# CONFIG_USARTn_2STOP - Two stop bits
#
CONFIG_SERIAL_TERMIOS=y
CONFIG_STANDARD_SERIAL=y
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
CONFIG_USART1_TXBUFSIZE=64
CONFIG_USART2_TXBUFSIZE=64
CONFIG_USART3_TXBUFSIZE=64
CONFIG_USART1_RXBUFSIZE=64
CONFIG_USART2_RXBUFSIZE=64
CONFIG_USART3_RXBUFSIZE=64
CONFIG_USART1_BAUD=115200
CONFIG_USART2_BAUD=115200
CONFIG_USART3_BAUD=115200
CONFIG_USART1_BITS=8
CONFIG_USART2_BITS=8
CONFIG_USART3_BITS=8
CONFIG_USART1_PARITY=0
CONFIG_USART2_PARITY=0
CONFIG_USART3_PARITY=0
CONFIG_USART1_2STOP=0
CONFIG_USART2_2STOP=0
CONFIG_USART3_2STOP=0
CONFIG_USART1_RXDMA=y
SERIAL_HAVE_CONSOLE_DMA=y
# Conflicts with I2C1 DMA
CONFIG_USART2_RXDMA=n
CONFIG_USART3_RXDMA=y
#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
# BSPs from www.ridgerun.com using the tools/mkimage.sh script
# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
# used with many different loaders using the GNU objcopy program
# Should not be selected if you are not using the GNU toolchain.
# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
# used with many different loaders using the GNU objcopy program
# Should not be selected if you are not using the GNU toolchain.
# CONFIG_RAW_BINARY - make a raw binary format file used with many
# different loaders using the GNU objcopy program. This option
# should not be selected if you are not using the GNU toolchain.
# CONFIG_HAVE_LIBM - toolchain supports libm.a
#
CONFIG_RRLOAD_BINARY=n
CONFIG_INTELHEX_BINARY=n
CONFIG_MOTOROLA_SREC=n
CONFIG_RAW_BINARY=y
CONFIG_HAVE_LIBM=n
#
# General OS setup
#
# CONFIG_APPS_DIR - Identifies the relative path to the directory
# that builds the application to link with NuttX. Default: ../apps
# CONFIG_DEBUG - enables built-in debug options
# CONFIG_DEBUG_VERBOSE - enables verbose debug output
# CONFIG_DEBUG_SYMBOLS - build without optimization and with
# debug symbols (needed for use with a debugger).
# CONFIG_HAVE_CXX - Enable support for C++
# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
# for initialization of static C++ instances for this architecture
# and for the selected toolchain (via up_cxxinitialize()).
# CONFIG_MM_REGIONS - If the architecture includes multiple
# regions of memory to allocate from, this specifies the
# number of memory regions that the memory manager must
# handle and enables the API mm_addregion(start, end);
# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
# time console output
# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
# or MSEC_PER_TICK=10. This setting may be defined to
# inform NuttX that the processor hardware is providing
# system timer interrupts at some interrupt interval other
# than 10 msec.
# CONFIG_RR_INTERVAL - The round robin timeslice will be set
# this number of milliseconds; Round robin scheduling can
# be disabled by setting this value to zero.
# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
# scheduler to monitor system performance
# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
# task name to save in the TCB. Useful if scheduler
# instrumentation is selected. Set to zero to disable.
# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
# Used to initialize the internal time logic.
# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
# You would only need this if you are concerned about accurate
# time conversions in the past or in the distant future.
# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
# would only need this if you are concerned about accurate
# time conversion in the distand past. You must also define
# CONFIG_GREGORIAN_TIME in order to use Julian time.
# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
# provides /dev/console. Enables stdout, stderr, stdin.
# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
# driver (minimul support)
# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
# errorcheck mutexes. Enables pthread_mutexattr_settype().
# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
# inheritance on mutexes and semaphores.
# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
# inheritance is enabled. It defines the maximum number of
# different threads (minus one) that can take counts on a
# semaphore with priority inheritance support. This may be
# set to zero if priority inheritance is disabled OR if you
# are only using semaphores as mutexes (only one holder) OR
# if no more than two threads participate using a counting
# semaphore.
# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
# then this setting is the maximum number of higher priority
# threads (minus 1) than can be waiting for another thread
# to release a count on a semaphore. This value may be set
# to zero if no more than one thread is expected to wait for
# a semaphore.
# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
# by task_create() when a new task is started. If set, all
# files/drivers will appear to be closed in the new task.
# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
# three file descriptors (stdin, stdout, stderr) by task_create()
# when a new task is started. If set, all files/drivers will
# appear to be closed in the new task except for stdin, stdout,
# and stderr.
# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
# desciptors by task_create() when a new task is started. If
# set, all sockets will appear to be closed in the new task.
# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
# handle delayed processing from interrupt handlers. This feature
# is required for some drivers but, if there are not complaints,
# can be safely disabled. The worker thread also performs
# garbage collection -- completing any delayed memory deallocations
# from interrupt handlers. If the worker thread is disabled,
# then that clean will be performed by the IDLE thread instead
# (which runs at the lowest of priority and may not be appropriate
# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
# is enabled, then the following options can also be used:
# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
# thread. Default: 50
# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
# work in units of microseconds. Default: 50*1000 (50 MS).
# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
# CONFIG_SCHED_WAITPID - Enable the waitpid() API
# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
CONFIG_USER_ENTRYPOINT="user_start"
#CONFIG_APPS_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_FS=n
CONFIG_DEBUG_GRAPHICS=n
CONFIG_DEBUG_LCD=n
CONFIG_DEBUG_USB=n
CONFIG_DEBUG_NET=n
CONFIG_DEBUG_RTC=n
CONFIG_DEBUG_ANALOG=n
CONFIG_DEBUG_PWM=n
CONFIG_DEBUG_CAN=n
CONFIG_DEBUG_I2C=n
CONFIG_DEBUG_INPUT=n
CONFIG_MSEC_PER_TICK=1
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_MM_REGIONS=1
CONFIG_MM_SMALL=y
CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=0
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=8
CONFIG_START_YEAR=1970
CONFIG_START_MONTH=1
CONFIG_START_DAY=1
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
# this eats ~1KiB of RAM ... work out why
CONFIG_DEV_CONSOLE=y
CONFIG_DEV_LOWCONSOLE=n
CONFIG_MUTEX_TYPES=n
CONFIG_PRIORITY_INHERITANCE=n
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_NNESTPRIO=0
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WORKQUEUE=n
CONFIG_SCHED_WORKPRIORITY=50
CONFIG_SCHED_WORKPERIOD=50000
CONFIG_SCHED_WORKSTACKSIZE=1024
CONFIG_SIG_SIGWORK=4
CONFIG_SCHED_WAITPID=n
CONFIG_SCHED_ATEXIT=n
#
# The following can be used to disable categories of
# APIs supported by the OS. If the compiler supports
# weak functions, then it should not be necessary to
# disable functions unless you want to restrict usage
# of those APIs.
#
# There are certain dependency relationships in these
# features.
#
# o mq_notify logic depends on signals to awaken tasks
# waiting for queues to become full or empty.
# o pthread_condtimedwait() depends on signals to wake
# up waiting tasks.
#
CONFIG_DISABLE_CLOCK=n
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_DISABLE_PTHREAD=y
CONFIG_DISABLE_SIGNALS=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_DISABLE_ENVIRON=y
CONFIG_DISABLE_POLL=y
#
# Misc libc settings
#
# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
# little smaller if we do not support fieldwidthes
#
CONFIG_NOPRINTF_FIELDWIDTH=n
#
# Allow for architecture optimized implementations
#
# The architecture can provide optimized versions of the
# following to improve system performance
#
CONFIG_ARCH_MEMCPY=n
CONFIG_ARCH_MEMCMP=n
CONFIG_ARCH_MEMMOVE=n
CONFIG_ARCH_MEMSET=n
CONFIG_ARCH_STRCMP=n
CONFIG_ARCH_STRCPY=n
CONFIG_ARCH_STRNCPY=n
CONFIG_ARCH_STRLEN=n
CONFIG_ARCH_STRNLEN=n
CONFIG_ARCH_BZERO=n
#
# Sizes of configurable things (0 disables)
#
# CONFIG_MAX_TASKS - The maximum number of simultaneously
# active tasks. This value must be a power of two.
# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
# of parameters that a task may receive (i.e., maxmum value
# of 'argc')
# CONFIG_NPTHREAD_KEYS - The number of items of thread-
# specific data that can be retained
# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
# descriptors (one for each open)
# CONFIG_NFILE_STREAMS - The maximum number of streams that
# can be fopen'ed
# CONFIG_NAME_MAX - The maximum size of a file name.
# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
# to force automatic, line-oriented flushing the output buffer
# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
# fprintf(), and vfprintf(). When a newline is encountered in
# the output string, the output buffer will be flushed. This
# (slightly) increases the NuttX footprint but supports the kind
# of behavior that people expect for printf().
# CONFIG_NUNGET_CHARS - Number of characters that can be
# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
# structures. The system manages a pool of preallocated
# message structures to minimize dynamic allocations
# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
# a fixed payload size given by this settin (does not include
# other message structure overhead.
# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
# can be passed to a watchdog handler
# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
# structures. The system manages a pool of preallocated
# watchdog structures to minimize dynamic allocations
# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
# timer structures. The system manages a pool of preallocated
# timer structures to minimize dynamic allocations. Set to
# zero for all dynamic allocations.
#
CONFIG_MAX_TASKS=4
CONFIG_MAX_TASK_ARGS=4
CONFIG_NPTHREAD_KEYS=2
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=0
CONFIG_NAME_MAX=12
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STDIO_LINEBUFFER=n
CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
CONFIG_MAX_WDOGPARMS=2
CONFIG_PREALLOC_WDOGS=4
CONFIG_PREALLOC_TIMERS=0
#
# Settings for apps/nshlib
#
# CONFIG_NSH_BUILTIN_APPS - Support external registered,
# "named" applications that can be executed from the NSH
# command line (see apps/README.txt for more information).
# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
# CONFIG_NSH_STRERROR - Use strerror(errno)
# CONFIG_NSH_LINELEN - Maximum length of one command line
# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
# CONFIG_NSH_DISABLEBG - Disable background commands
# CONFIG_NSH_ROMFSETC - Use startup script in /etc
# CONFIG_NSH_CONSOLE - Use serial console front end
# CONFIG_NSH_TELNET - Use telnetd console front end
# CONFIG_NSH_ARCHINIT - Platform provides architecture
# specific initialization (nsh_archinitialize()).
#
# Disable NSH completely
CONFIG_NSH_CONSOLE=n
#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
# operation from FLASH but must copy initialized .data sections to RAM.
# (should also be =n for the STM3210E-EVAL which always runs from flash)
# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
# but copy themselves entirely into RAM for better performance.
# CONFIG_CUSTOM_STACK - The up_ implementation will handle
# all stack operations outside of the nuttx model.
# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
# This is the thread that (1) performs the inital boot of the system up
# to the point where user_start() is spawned, and (2) there after is the
# IDLE thread that executes only when there is no other thread ready to
# run.
# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
# for the main user thread that begins at the user_start() entry point.
# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
# CONFIG_HEAP_BASE - The beginning of the heap
# CONFIG_HEAP_SIZE - The size of the heap
#
CONFIG_BOOT_RUNFROMFLASH=n
CONFIG_BOOT_COPYTORAM=n
CONFIG_CUSTOM_STACK=n
CONFIG_STACK_POINTER=
CONFIG_IDLETHREAD_STACKSIZE=1024
CONFIG_USERMAIN_STACKSIZE=1200
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=1024
CONFIG_HEAP_BASE=
CONFIG_HEAP_SIZE=
#
# NSH Library
#
# CONFIG_NSH_LIBRARY is not set
# CONFIG_NSH_BUILTIN_APPS is not set
+47
View File
@@ -0,0 +1,47 @@
#!/bin/bash
# configs/stm3210e-eval/dfu/setenv.sh
#
# Copyright (C) 2009 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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 NuttX 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.
#
if [ "$(basename $0)" = "setenv.sh" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
+129
View File
@@ -0,0 +1,129 @@
/****************************************************************************
* configs/stm3210e-eval/nsh/ld.script
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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 NuttX 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.
*
****************************************************************************/
/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and
* 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
* FLASH memory is aliased to address 0x0000:0000 where the code expects to
* begin execution by jumping to the entry point in the 0x0800:0000 address
* range.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
/* The STM32F100CB has 8Kb of SRAM beginning at the following address */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
+84
View File
@@ -0,0 +1,84 @@
############################################################################
# configs/stm3210e-eval/src/Makefile
#
# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# 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 NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
-include $(TOPDIR)/Make.defs
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = empty.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(WINTOOL),y)
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
else
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
endif
all: libboard$(LIBEXT)
$(AOBJS): %$(OBJEXT): %.S
$(call ASSEMBLE, $<, $@)
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
libboard$(LIBEXT): $(OBJS)
$(call ARCHIVE, $@, $(OBJS))
.depend: Makefile $(SRCS)
@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
depend: .depend
clean:
$(call DELFILE, libboard$(LIBEXT))
$(call CLEAN)
distclean: clean
$(call DELFILE, Make.dep)
$(call DELFILE, .depend)
-include Make.dep
+4
View File
@@ -0,0 +1,4 @@
/*
* There are no source files here, but libboard.a can't be empty, so
* we have this empty source file to keep it company.
*/
+8 -8
View File
@@ -111,21 +111,21 @@ CDev::~CDev()
int
CDev::init()
{
int ret = OK;
// base class init first
ret = Device::init();
int ret = Device::init();
if (ret != OK)
goto out;
// now register the driver
ret = register_driver(_devname, &fops, 0666, (void *)this);
if (_devname != nullptr) {
ret = register_driver(_devname, &fops, 0666, (void *)this);
if (ret != OK)
goto out;
if (ret != OK)
goto out;
_registered = true;
_registered = true;
}
out:
return ret;
@@ -395,4 +395,4 @@ cdev_poll(struct file *filp, struct pollfd *fds, bool setup)
return cdev->poll(filp, fds, setup);
}
} // namespace device
} // namespace device
+18 -1
View File
@@ -223,5 +223,22 @@ interrupt(int irq, void *context)
return OK;
}
int
Device::read(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
} // namespace device
int
Device::write(unsigned offset, void *data, unsigned count)
{
return -ENODEV;
}
int
Device::ioctl(unsigned operation, unsigned &arg)
{
return -ENODEV;
}
} // namespace device
+57 -13
View File
@@ -68,11 +68,62 @@ namespace device __EXPORT
class __EXPORT Device
{
public:
/**
* Destructor.
*
* Public so that anonymous devices can be destroyed.
*/
virtual ~Device();
/**
* Interrupt handler.
*/
virtual void interrupt(void *ctx); /**< interrupt handler */
/*
* Direct access methods.
*/
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialized OK, negative errno otherwise;
*/
virtual int init();
/**
* Read directly from the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param offset The device address at which to start reading
* @param data The buffer into which the read values should be placed.
* @param count The number of items to read.
* @return The number of items read on success, negative errno otherwise.
*/
virtual int read(unsigned address, void *data, unsigned count);
/**
* Write directly to the device.
*
* The actual size of each unit quantity is device-specific.
*
* @param address The device address at which to start writing.
* @param data The buffer from which values should be read.
* @param count The number of items to write.
* @return The number of items written on success, negative errno otherwise.
*/
virtual int write(unsigned address, void *data, unsigned count);
/**
* Perform a device-specific operation.
*
* @param operation The operation to perform.
* @param arg An argument to the operation.
* @return Negative errno on error, OK or positive value on success.
*/
virtual int ioctl(unsigned operation, unsigned &arg);
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
@@ -85,14 +136,6 @@ protected:
*/
Device(const char *name,
int irq = 0);
~Device();
/**
* Initialise the driver and make it ready for use.
*
* @return OK if the driver initialised OK.
*/
virtual int init();
/**
* Enable the device interrupt
@@ -189,7 +232,7 @@ public:
/**
* Destructor
*/
~CDev();
virtual ~CDev();
virtual int init();
@@ -282,6 +325,7 @@ public:
* Test whether the device is currently open.
*
* This can be used to avoid tearing down a device that is still active.
* Note - not virtual, cannot be overridden by a subclass.
*
* @return True if the device is currently open.
*/
@@ -396,9 +440,9 @@ public:
const char *devname,
uint32_t base,
int irq = 0);
~PIO();
virtual ~PIO();
int init();
virtual int init();
protected:
@@ -407,7 +451,7 @@ protected:
*
* @param offset Register offset in bytes from the base address.
*/
uint32_t reg(uint32_t offset) {
uint32_t reg(uint32_t offset) {
return *(volatile uint32_t *)(_base + offset);
}
@@ -444,4 +488,4 @@ private:
} // namespace device
#endif /* _DEVICE_DEVICE_H */
#endif /* _DEVICE_DEVICE_H */
+6 -8
View File
@@ -55,13 +55,11 @@ class __EXPORT I2C : public CDev
public:
/**
* Get the address
*/
uint16_t get_address() {
return _address;
}
/**
* Get the address
*/
int16_t get_address() { return _address; }
protected:
/**
* The number of times a read or write operation will be retried on
@@ -90,7 +88,7 @@ protected:
uint16_t address,
uint32_t frequency,
int irq = 0);
~I2C();
virtual ~I2C();
virtual int init();
+203
View File
@@ -0,0 +1,203 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ringbuffer.h
*
* A simple ringbuffer template.
*/
#pragma once
template<typename T>
class RingBuffer {
public:
RingBuffer(unsigned size);
virtual ~RingBuffer();
/**
* Put an item into the buffer.
*
* @param val Item to put
* @return true if the item was put, false if the buffer is full
*/
bool put(T &val);
/**
* Put an item into the buffer.
*
* @param val Item to put
* @return true if the item was put, false if the buffer is full
*/
bool put(const T &val);
/**
* Get an item from the buffer.
*
* @param val Item that was gotten
* @return true if an item was got, false if the buffer was empty.
*/
bool get(T &val);
/**
* Get an item from the buffer (scalars only).
*
* @return The value that was fetched, or zero if the buffer was
* empty.
*/
T get(void);
/*
* Get the number of slots free in the buffer.
*
* @return The number of items that can be put into the buffer before
* it becomes full.
*/
unsigned space(void);
/*
* Get the number of items in the buffer.
*
* @return The number of items that can be got from the buffer before
* it becomes empty.
*/
unsigned count(void);
/*
* Returns true if the buffer is empty.
*/
bool empty() { return _tail == _head; }
/*
* Returns true if the buffer is full.
*/
bool full() { return _next(_head) == _tail; }
/*
* Returns the capacity of the buffer, or zero if the buffer could
* not be allocated.
*/
unsigned size() { return (_buf != nullptr) ? _size : 0; }
/*
* Empties the buffer.
*/
void flush() { _head = _tail = _size; }
private:
T *const _buf;
const unsigned _size;
volatile unsigned _head; /**< insertion point */
volatile unsigned _tail; /**< removal point */
unsigned _next(unsigned index);
};
template <typename T>
RingBuffer<T>::RingBuffer(unsigned with_size) :
_buf(new T[with_size + 1]),
_size(with_size),
_head(with_size),
_tail(with_size)
{}
template <typename T>
RingBuffer<T>::~RingBuffer()
{
if (_buf != nullptr)
delete[] _buf;
}
template <typename T>
bool RingBuffer<T>::put(T &val)
{
unsigned next = _next(_head);
if (next != _tail) {
_buf[_head] = val;
_head = next;
return true;
} else {
return false;
}
}
template <typename T>
bool RingBuffer<T>::put(const T &val)
{
unsigned next = _next(_head);
if (next != _tail) {
_buf[_head] = val;
_head = next;
return true;
} else {
return false;
}
}
template <typename T>
bool RingBuffer<T>::get(T &val)
{
if (_tail != _head) {
val = _buf[_tail];
_tail = _next(_tail);
return true;
} else {
return false;
}
}
template <typename T>
T RingBuffer<T>::get(void)
{
T val;
return get(val) ? val : 0;
}
template <typename T>
unsigned RingBuffer<T>::space(void)
{
return (_tail >= _head) ? (_size - (_tail - _head)) : (_head - _tail - 1);
}
template <typename T>
unsigned RingBuffer<T>::count(void)
{
return _size - space();
}
template <typename T>
unsigned RingBuffer<T>::_next(unsigned index)
{
return (0 == index) ? _size : (index - 1);
}
+1 -1
View File
@@ -71,7 +71,7 @@ protected:
enum spi_mode_e mode,
uint32_t frequency,
int irq = 0);
~SPI();
virtual ~SPI();
virtual int init();
+1 -4
View File
@@ -118,11 +118,8 @@ ORB_DECLARE(output_pwm);
/** start DSM bind */
#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7)
/** stop DSM bind */
#define DSM_BIND_STOP _IOC(_PWM_SERVO_BASE, 8)
/** Power up DSM receiver */
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 9)
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8)
/** set a single servo to a specific value */
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
@@ -383,6 +383,10 @@ test()
warnx("diff pressure: %d pa", report.differential_pressure_pa);
}
/* reset the sensor polling to its default rate */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
errx(1, "failed to set default rate");
errx(0, "PASS");
}
+7 -2
View File
@@ -333,8 +333,13 @@ L3GD20::init()
write_reg(ADDR_CTRL_REG4, REG4_BDU);
write_reg(ADDR_CTRL_REG5, 0);
write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */
write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
/* disable FIFO. This makes things simpler and ensures we
* aren't getting stale data. It means we must run the hrt
* callback fast enough to not miss data. */
write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
set_range(500); /* default to 500dps */
set_samplerate(0); /* max sample rate */
+8
View File
@@ -0,0 +1,8 @@
#include "BlockSysIdent.hpp"
BlockSysIdent::BlockSysIdent() :
Block(NULL, "SYSID"),
_freq(this, "FREQ"),
_ampl(this, "AMPL")
{
}
+10
View File
@@ -0,0 +1,10 @@
#include <controllib/block/Block.hpp>
#include <controllib/block/BlockParam.hpp>
class BlockSysIdent : public control::Block {
public:
BlockSysIdent();
private:
control::BlockParam<float> _freq;
control::BlockParam<float> _ampl;
};
+84 -3
View File
@@ -45,9 +45,16 @@
#include "md25.hpp"
#include <poll.h>
#include <stdio.h>
#include <math.h>
#include <string.h>
#include <systemlib/err.h>
#include <arch/board/board.h>
#include <mavlink/mavlink_log.h>
#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/topics/debug_key_value.h>
#include <drivers/drv_hrt.h>
// registers
enum {
@@ -72,6 +79,9 @@ enum {
REG_COMMAND_RW,
};
// File descriptors
static int mavlink_fd;
MD25::MD25(const char *deviceName, int bus,
uint16_t address, uint32_t speed) :
I2C("MD25", deviceName, bus, address, speed),
@@ -106,7 +116,8 @@ MD25::MD25(const char *deviceName, int bus,
setMotor2Speed(0);
resetEncoders();
_setMode(MD25::MODE_UNSIGNED_SPEED);
setSpeedRegulation(true);
setSpeedRegulation(false);
setMotorAccel(10);
setTimeout(true);
}
@@ -298,6 +309,12 @@ int MD25::setDeviceAddress(uint8_t address)
return OK;
}
int MD25::setMotorAccel(uint8_t accel)
{
return _writeUint8(REG_ACCEL_RATE_RW,
accel);
}
int MD25::setMotor1Speed(float value)
{
return _writeUint8(REG_SPEED1_RW,
@@ -451,12 +468,12 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address)
MD25 md25("/dev/md25", bus, address);
// print status
char buf[200];
char buf[400];
md25.status(buf, sizeof(buf));
printf("%s\n", buf);
// setup for test
md25.setSpeedRegulation(true);
md25.setSpeedRegulation(false);
md25.setTimeout(true);
float dt = 0.1;
float speed = 0.2;
@@ -550,4 +567,68 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address)
return 0;
}
int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency)
{
printf("md25 sine: starting\n");
// setup
MD25 md25("/dev/md25", bus, address);
// print status
char buf[400];
md25.status(buf, sizeof(buf));
printf("%s\n", buf);
// setup for test
md25.setSpeedRegulation(false);
md25.setTimeout(true);
float dt = 0.01;
float t_final = 60.0;
float prev_revolution = md25.getRevolutions1();
// debug publication
control::UOrbPublication<debug_key_value_s> debug_msg(NULL,
ORB_ID(debug_key_value));
// sine wave for motor 1
md25.resetEncoders();
while (true) {
// input
uint64_t timestamp = hrt_absolute_time();
float t = timestamp/1000000.0f;
float input_value = amplitude*sinf(2*M_PI*frequency*t);
md25.setMotor1Speed(input_value);
// output
md25.readData();
float current_revolution = md25.getRevolutions1();
// send input message
//strncpy(debug_msg.key, "md25 in ", 10);
//debug_msg.timestamp_ms = 1000*timestamp;
//debug_msg.value = input_value;
//debug_msg.update();
// send output message
strncpy(debug_msg.key, "md25 out ", 10);
debug_msg.timestamp_ms = 1000*timestamp;
debug_msg.value = current_revolution;
debug_msg.update();
if (t > t_final) break;
// update for next step
prev_revolution = current_revolution;
// sleep
usleep(1000000 * dt);
}
md25.setMotor1Speed(0);
printf("md25 sine complete\n");
return 0;
}
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
+17 -1
View File
@@ -46,7 +46,7 @@
#include <poll.h>
#include <stdio.h>
#include <controllib/block/UOrbSubscription.hpp>
#include <controllib/uorb/UOrbSubscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <drivers/device/i2c.h>
@@ -212,6 +212,19 @@ public:
*/
int setDeviceAddress(uint8_t address);
/**
* set motor acceleration
* @param accel
* controls motor speed change (1-10)
* accel rate | time for full fwd. to full rev.
* 1 | 6.375 s
* 2 | 1.6 s
* 3 | 0.675 s
* 5(default) | 1.275 s
* 10 | 0.65 s
*/
int setMotorAccel(uint8_t accel);
/**
* set motor 1 speed
* @param normSpeed normalize speed between -1 and 1
@@ -290,4 +303,7 @@ private:
// unit testing
int md25Test(const char *deviceName, uint8_t bus, uint8_t address);
// sine testing
int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency);
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
+47 -2
View File
@@ -82,7 +82,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
fprintf(stderr, "usage: md25 {start|stop|status|search|test|change_address}\n\n");
fprintf(stderr, "usage: md25 {start|stop|read|status|search|test|change_address}\n\n");
exit(1);
}
@@ -136,6 +136,28 @@ int md25_main(int argc, char *argv[])
exit(0);
}
if (!strcmp(argv[1], "sine")) {
if (argc < 6) {
printf("usage: md25 sine bus address amp freq\n");
exit(0);
}
const char *deviceName = "/dev/md25";
uint8_t bus = strtoul(argv[2], nullptr, 0);
uint8_t address = strtoul(argv[3], nullptr, 0);
float amplitude = atof(argv[4]);
float frequency = atof(argv[5]);
md25Sine(deviceName, bus, address, amplitude, frequency);
exit(0);
}
if (!strcmp(argv[1], "probe")) {
if (argc < 4) {
printf("usage: md25 probe bus address\n");
@@ -162,6 +184,29 @@ int md25_main(int argc, char *argv[])
exit(0);
}
if (!strcmp(argv[1], "read")) {
if (argc < 4) {
printf("usage: md25 read bus address\n");
exit(0);
}
const char *deviceName = "/dev/md25";
uint8_t bus = strtoul(argv[2], nullptr, 0);
uint8_t address = strtoul(argv[3], nullptr, 0);
MD25 md25(deviceName, bus, address);
// print status
char buf[400];
md25.status(buf, sizeof(buf));
printf("%s\n", buf);
exit(0);
}
if (!strcmp(argv[1], "search")) {
if (argc < 3) {
printf("usage: md25 search bus\n");
@@ -246,7 +291,7 @@ int md25_thread_main(int argc, char *argv[])
uint8_t address = strtoul(argv[4], nullptr, 0);
// start
MD25 md25("/dev/md25", bus, address);
MD25 md25(deviceName, bus, address);
thread_running = true;
+26 -12
View File
@@ -34,6 +34,7 @@
/**
* @file meas_airspeed.cpp
* @author Lorenz Meier
* @author Sarthak Kaingade
* @author Simon Wilks
*
* Driver for the MEAS Spec series connected via I2C.
@@ -92,9 +93,6 @@
/* Register address */
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */
#define ADDR_READ_DF3 0x01
#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
@@ -122,7 +120,7 @@ protected:
extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address,
CONVERSION_INTERVAL)
CONVERSION_INTERVAL)
{
}
@@ -160,7 +158,7 @@ MEASAirspeed::collect()
perf_begin(_sample_perf);
ret = transfer(nullptr, 0, &val[0], 2);
ret = transfer(nullptr, 0, &val[0], 4);
if (ret < 0) {
log("error reading from sensor: %d", ret);
@@ -171,25 +169,37 @@ MEASAirspeed::collect()
if (status == 2) {
log("err: stale data");
} else if (status == 3) {
log("err: fault");
}
uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
//uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
uint16_t temp = (val[3] & 0xE0) << 8 | val[2];
diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
diff_pres_pa -= _diff_pres_offset;
// XXX leaving this in until new calculation method has been cross-checked
//diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
//diff_pres_pa -= _diff_pres_offset;
int16_t dp_raw = 0, dT_raw = 0;
dp_raw = (val[0] << 8) + val[1];
dp_raw = 0x3FFF & dp_raw;
dT_raw = (val[2] << 8) + val[3];
dT_raw = (0xFFE0 & dT_raw) >> 5;
float temperature = ((200 * dT_raw) / 2047) - 50;
// XXX we may want to smooth out the readings to remove noise.
// Calculate differential pressure. As its centered around 8000
// and can go positive or negative, enforce absolute value
uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f));
_reports[_next_report].timestamp = hrt_absolute_time();
_reports[_next_report].temperature = temp;
_reports[_next_report].differential_pressure_pa = diff_pres_pa;
_reports[_next_report].temperature = temperature;
_reports[_next_report].differential_pressure_pa = diff_press_pa;
// Track maximum differential pressure measured (so we can work out top speed).
if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) {
_reports[_next_report].max_differential_pressure_pa = diff_pres_pa;
if (diff_press_pa > _reports[_next_report].max_differential_pressure_pa) {
_reports[_next_report].max_differential_pressure_pa = diff_press_pa;
}
/* announce the airspeed if needed, just publish else */
@@ -405,6 +415,10 @@ test()
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}
/* reset the sensor polling to its default rate */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
errx(1, "failed to set default rate");
errx(0, "PASS");
}
+280 -100
View File
@@ -67,8 +67,10 @@
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
@@ -181,13 +183,17 @@ private:
struct hrt_call _call;
unsigned _call_interval;
struct accel_report _accel_report;
typedef RingBuffer<accel_report> AccelReportBuffer;
AccelReportBuffer *_accel_reports;
struct accel_scale _accel_scale;
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
struct gyro_report _gyro_report;
typedef RingBuffer<gyro_report> GyroReportBuffer;
GyroReportBuffer *_gyro_reports;
struct gyro_scale _gyro_scale;
float _gyro_range_scale;
float _gyro_range_rad_s;
@@ -197,6 +203,13 @@ private:
unsigned _sample_rate;
perf_counter_t _sample_perf;
math::LowPassFilter2p _accel_filter_x;
math::LowPassFilter2p _accel_filter_y;
math::LowPassFilter2p _accel_filter_z;
math::LowPassFilter2p _gyro_filter_x;
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
/**
* Start automatic measurement.
*/
@@ -207,6 +220,13 @@ private:
*/
void stop();
/**
* Reset chip.
*
* Resets the chip and measurements ranges, but not scale and offset.
*/
void reset();
/**
* Static trampoline from the hrt_call context; because we don't have a
* generic hrt wrapper yet.
@@ -219,7 +239,7 @@ private:
static void measure_trampoline(void *arg);
/**
* Fetch measurements from the sensor and update the report ring.
* Fetch measurements from the sensor and update the report buffers.
*/
void measure();
@@ -311,15 +331,23 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro(new MPU6000_gyro(this)),
_product(0),
_call_interval(0),
_accel_reports(nullptr),
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
_gyro_reports(nullptr),
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_gyro_topic(-1),
_reads(0),
_sample_rate(500),
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read"))
_sample_rate(1000),
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")),
_accel_filter_x(1000, 30),
_accel_filter_y(1000, 30),
_accel_filter_z(1000, 30),
_gyro_filter_x(1000, 30),
_gyro_filter_y(1000, 30),
_gyro_filter_z(1000, 30)
{
// disable debug() calls
_debug_enabled = false;
@@ -340,8 +368,6 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro_scale.z_offset = 0;
_gyro_scale.z_scale = 1.0f;
memset(&_accel_report, 0, sizeof(_accel_report));
memset(&_gyro_report, 0, sizeof(_gyro_report));
memset(&_call, 0, sizeof(_call));
}
@@ -353,6 +379,12 @@ MPU6000::~MPU6000()
/* delete the gyro subdriver */
delete _gyro;
/* free any existing reports */
if (_accel_reports != nullptr)
delete _accel_reports;
if (_gyro_reports != nullptr)
delete _gyro_reports;
/* delete the perf counter */
perf_free(_sample_perf);
}
@@ -361,6 +393,7 @@ int
MPU6000::init()
{
int ret;
int gyro_ret;
/* do SPI init (and probe) first */
ret = SPI::init();
@@ -371,6 +404,59 @@ MPU6000::init()
return ret;
}
/* allocate basic report buffers */
_accel_reports = new AccelReportBuffer(2);
if (_accel_reports == nullptr)
goto out;
_gyro_reports = new GyroReportBuffer(2);
if (_gyro_reports == nullptr)
goto out;
reset();
/* Initialize offsets and scales */
_accel_scale.x_offset = 0;
_accel_scale.x_scale = 1.0f;
_accel_scale.y_offset = 0;
_accel_scale.y_scale = 1.0f;
_accel_scale.z_offset = 0;
_accel_scale.z_scale = 1.0f;
_gyro_scale.x_offset = 0;
_gyro_scale.x_scale = 1.0f;
_gyro_scale.y_offset = 0;
_gyro_scale.y_scale = 1.0f;
_gyro_scale.z_offset = 0;
_gyro_scale.z_scale = 1.0f;
/* do CDev init for the gyro device node, keep it optional */
gyro_ret = _gyro->init();
/* fetch an initial set of measurements for advertisement */
measure();
if (gyro_ret != OK) {
_gyro_topic = -1;
} else {
gyro_report gr;
_gyro_reports->get(gr);
_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr);
}
/* advertise accel topic */
accel_report ar;
_accel_reports->get(ar);
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar);
out:
return ret;
}
void MPU6000::reset()
{
// Chip reset
write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
up_udelay(10000);
@@ -391,7 +477,7 @@ MPU6000::init()
// FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter)
// was 90 Hz, but this ruins quality and does not improve the
// system response
_set_dlpf_filter(20);
_set_dlpf_filter(42);
usleep(1000);
// Gyro scale 2000 deg/s ()
write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS);
@@ -402,12 +488,6 @@ MPU6000::init()
// 2000 deg/s = (2000/180)*PI = 34.906585 rad/s
// scaling factor:
// 1/(2^15)*(2000/180)*PI
_gyro_scale.x_offset = 0;
_gyro_scale.x_scale = 1.0f;
_gyro_scale.y_offset = 0;
_gyro_scale.y_scale = 1.0f;
_gyro_scale.z_offset = 0;
_gyro_scale.z_scale = 1.0f;
_gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F);
_gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F;
@@ -440,12 +520,6 @@ MPU6000::init()
// Correct accel scale factors of 4096 LSB/g
// scale to m/s^2 ( 1g = 9.81 m/s^2)
_accel_scale.x_offset = 0;
_accel_scale.x_scale = 1.0f;
_accel_scale.y_offset = 0;
_accel_scale.y_scale = 1.0f;
_accel_scale.z_offset = 0;
_accel_scale.z_scale = 1.0f;
_accel_range_scale = (9.81f / 4096.0f);
_accel_range_m_s2 = 8.0f * 9.81f;
@@ -461,22 +535,6 @@ MPU6000::init()
// write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
usleep(1000);
/* do CDev init for the gyro device node, keep it optional */
int gyro_ret = _gyro->init();
/* ensure we got real values to share */
measure();
if (gyro_ret != OK) {
_gyro_topic = -1;
} else {
_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report);
}
/* advertise sensor topics */
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report);
return ret;
}
int
@@ -555,21 +613,33 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz)
ssize_t
MPU6000::read(struct file *filp, char *buffer, size_t buflen)
{
int ret = 0;
unsigned count = buflen / sizeof(accel_report);
/* buffer must be large enough */
if (buflen < sizeof(_accel_report))
if (count < 1)
return -ENOSPC;
/* if automatic measurement is not enabled */
if (_call_interval == 0)
/* if automatic measurement is not enabled, get a fresh measurement into the buffer */
if (_call_interval == 0) {
_accel_reports->flush();
measure();
}
/* copy out the latest reports */
memcpy(buffer, &_accel_report, sizeof(_accel_report));
ret = sizeof(_accel_report);
/* if no data, error (we could block here) */
if (_accel_reports->empty())
return -EAGAIN;
return ret;
/* copy reports out of our buffer to the caller */
accel_report *arp = reinterpret_cast<accel_report *>(buffer);
int transferred = 0;
while (count--) {
if (!_accel_reports->get(*arp++))
break;
transferred++;
}
/* return the number of bytes transferred */
return (transferred * sizeof(accel_report));
}
int
@@ -586,21 +656,33 @@ MPU6000::self_test()
ssize_t
MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
int ret = 0;
unsigned count = buflen / sizeof(gyro_report);
/* buffer must be large enough */
if (buflen < sizeof(_gyro_report))
if (count < 1)
return -ENOSPC;
/* if automatic measurement is not enabled */
if (_call_interval == 0)
/* if automatic measurement is not enabled, get a fresh measurement into the buffer */
if (_call_interval == 0) {
_gyro_reports->flush();
measure();
}
/* copy out the latest report */
memcpy(buffer, &_gyro_report, sizeof(_gyro_report));
ret = sizeof(_gyro_report);
/* if no data, error (we could block here) */
if (_gyro_reports->empty())
return -EAGAIN;
return ret;
/* copy reports out of our buffer to the caller */
gyro_report *arp = reinterpret_cast<gyro_report *>(buffer);
int transferred = 0;
while (count--) {
if (!_gyro_reports->get(*arp++))
break;
transferred++;
}
/* return the number of bytes transferred */
return (transferred * sizeof(gyro_report));
}
int
@@ -608,6 +690,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
case SENSORIOCRESET:
reset();
return OK;
case SENSORIOCSPOLLRATE: {
switch (arg) {
@@ -627,8 +713,8 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
/* XXX 500Hz is just a wild guess */
return ioctl(filp, SENSORIOCSPOLLRATE, 500);
/* set to same as sample rate per default */
return ioctl(filp, SENSORIOCSPOLLRATE, _sample_rate);
/* adjust to a legal polling interval in Hz */
default: {
@@ -642,6 +728,19 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
if (ticks < 1000)
return -EINVAL;
// adjust filters
float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq();
float sample_rate = 1.0e6f/ticks;
_accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
_accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
_accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq();
_gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
_gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
_gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
/* update interval for next measurement */
/* XXX this is a bit shady, but no other way to adjust... */
_call.period = _call_interval = ticks;
@@ -661,25 +760,51 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return 1000000 / _call_interval;
case SENSORIOCSQUEUEDEPTH:
/* XXX not implemented */
return -EINVAL;
case SENSORIOCSQUEUEDEPTH: {
/* lower bound is mandatory, upper bound is a sanity check */
if ((arg < 1) || (arg > 100))
return -EINVAL;
/* allocate new buffer */
AccelReportBuffer *buf = new AccelReportBuffer(arg);
if (nullptr == buf)
return -ENOMEM;
if (buf->size() == 0) {
delete buf;
return -ENOMEM;
}
/* reset the measurement state machine with the new buffer, free the old */
stop();
delete _accel_reports;
_accel_reports = buf;
start();
return OK;
}
case SENSORIOCGQUEUEDEPTH:
/* XXX not implemented */
return -EINVAL;
return _accel_reports->size();
case ACCELIOCGSAMPLERATE:
return _sample_rate;
case ACCELIOCSSAMPLERATE:
_set_sample_rate(arg);
return OK;
_set_sample_rate(arg);
return OK;
case ACCELIOCGLOWPASS:
return _accel_filter_x.get_cutoff_freq();
case ACCELIOCSLOWPASS:
case ACCELIOCGLOWPASS:
_set_dlpf_filter((uint16_t)arg);
// XXX decide on relationship of both filters
// i.e. disable the on-chip filter
//_set_dlpf_filter((uint16_t)arg);
_accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
return OK;
case ACCELIOCSSCALE:
@@ -726,11 +851,36 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
/* these are shared with the accel side */
case SENSORIOCSPOLLRATE:
case SENSORIOCGPOLLRATE:
case SENSORIOCSQUEUEDEPTH:
case SENSORIOCGQUEUEDEPTH:
case SENSORIOCRESET:
return ioctl(filp, cmd, arg);
case SENSORIOCSQUEUEDEPTH: {
/* lower bound is mandatory, upper bound is a sanity check */
if ((arg < 1) || (arg > 100))
return -EINVAL;
/* allocate new buffer */
GyroReportBuffer *buf = new GyroReportBuffer(arg);
if (nullptr == buf)
return -ENOMEM;
if (buf->size() == 0) {
delete buf;
return -ENOMEM;
}
/* reset the measurement state machine with the new buffer, free the old */
stop();
delete _gyro_reports;
_gyro_reports = buf;
start();
return OK;
}
case SENSORIOCGQUEUEDEPTH:
return _gyro_reports->size();
case GYROIOCGSAMPLERATE:
return _sample_rate;
@@ -738,9 +888,14 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
_set_sample_rate(arg);
return OK;
case GYROIOCSLOWPASS:
case GYROIOCGLOWPASS:
_set_dlpf_filter((uint16_t)arg);
return _gyro_filter_x.get_cutoff_freq();
case GYROIOCSLOWPASS:
_gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
// XXX check relation to the internal lowpass
//_set_dlpf_filter((uint16_t)arg);
return OK;
case GYROIOCSSCALE:
@@ -865,6 +1020,10 @@ MPU6000::start()
/* make sure we are stopped first */
stop();
/* discard any stale data in the buffers */
_accel_reports->flush();
_gyro_reports->flush();
/* start polling at the specified rate */
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&MPU6000::measure_trampoline, this);
}
@@ -878,7 +1037,7 @@ MPU6000::stop()
void
MPU6000::measure_trampoline(void *arg)
{
MPU6000 *dev = (MPU6000 *)arg;
MPU6000 *dev = reinterpret_cast<MPU6000 *>(arg);
/* make another measurement */
dev->measure();
@@ -959,10 +1118,16 @@ MPU6000::measure()
report.gyro_x = gyro_xt;
report.gyro_y = gyro_yt;
/*
* Report buffers.
*/
accel_report arb;
gyro_report grb;
/*
* Adjust and scale results to m/s^2.
*/
_gyro_report.timestamp = _accel_report.timestamp = hrt_absolute_time();
grb.timestamp = arb.timestamp = hrt_absolute_time();
/*
@@ -983,40 +1148,53 @@ MPU6000::measure()
/* NOTE: Axes have been swapped to match the board a few lines above. */
_accel_report.x_raw = report.accel_x;
_accel_report.y_raw = report.accel_y;
_accel_report.z_raw = report.accel_z;
arb.x_raw = report.accel_x;
arb.y_raw = report.accel_y;
arb.z_raw = report.accel_z;
_accel_report.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
_accel_report.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
_accel_report.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
_accel_report.scaling = _accel_range_scale;
_accel_report.range_m_s2 = _accel_range_m_s2;
float x_in_new = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
float y_in_new = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
float z_in_new = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
arb.x = _accel_filter_x.apply(x_in_new);
arb.y = _accel_filter_y.apply(y_in_new);
arb.z = _accel_filter_z.apply(z_in_new);
_accel_report.temperature_raw = report.temp;
_accel_report.temperature = (report.temp) / 361.0f + 35.0f;
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
_gyro_report.x_raw = report.gyro_x;
_gyro_report.y_raw = report.gyro_y;
_gyro_report.z_raw = report.gyro_z;
arb.temperature_raw = report.temp;
arb.temperature = (report.temp) / 361.0f + 35.0f;
_gyro_report.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
_gyro_report.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
_gyro_report.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
_gyro_report.scaling = _gyro_range_scale;
_gyro_report.range_rad_s = _gyro_range_rad_s;
grb.x_raw = report.gyro_x;
grb.y_raw = report.gyro_y;
grb.z_raw = report.gyro_z;
_gyro_report.temperature_raw = report.temp;
_gyro_report.temperature = (report.temp) / 361.0f + 35.0f;
float x_gyro_in_new = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
float y_gyro_in_new = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
float z_gyro_in_new = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
grb.x = _gyro_filter_x.apply(x_gyro_in_new);
grb.y = _gyro_filter_y.apply(y_gyro_in_new);
grb.z = _gyro_filter_z.apply(z_gyro_in_new);
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
grb.temperature = (report.temp) / 361.0f + 35.0f;
_accel_reports->put(arb);
_gyro_reports->put(grb);
/* notify anyone waiting for data */
poll_notify(POLLIN);
_gyro->parent_poll_notify();
/* and publish for subscribers */
orb_publish(ORB_ID(sensor_accel), _accel_topic, &_accel_report);
orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb);
if (_gyro_topic != -1) {
orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report);
orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &grb);
}
/* stop measuring */
@@ -1119,21 +1297,19 @@ fail:
void
test()
{
int fd = -1;
int fd_gyro = -1;
struct accel_report a_report;
struct gyro_report g_report;
accel_report a_report;
gyro_report g_report;
ssize_t sz;
/* get the driver */
fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
ACCEL_DEVICE_PATH);
/* get the driver */
fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
int fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
if (fd_gyro < 0)
err(1, "%s open failed", GYRO_DEVICE_PATH);
@@ -1145,8 +1321,10 @@ test()
/* do a simple demand read */
sz = read(fd, &a_report, sizeof(a_report));
if (sz != sizeof(a_report))
if (sz != sizeof(a_report)) {
warnx("ret: %d, expected: %d", sz, sizeof(a_report));
err(1, "immediate acc read failed");
}
warnx("single read");
warnx("time: %lld", a_report.timestamp);
@@ -1162,8 +1340,10 @@ test()
/* do a simple demand read */
sz = read(fd_gyro, &g_report, sizeof(g_report));
if (sz != sizeof(g_report))
if (sz != sizeof(g_report)) {
warnx("ret: %d, expected: %d", sz, sizeof(g_report));
err(1, "immediate gyro read failed");
}
warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
+114 -67
View File
@@ -89,21 +89,61 @@
#define PX4IO_SET_DEBUG _IOC(0xff00, 0)
#define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1)
/**
* The PX4IO class.
*
* Encapsulates PX4FMU to PX4IO communications modeled as file operations.
*/
class PX4IO : public device::I2C
{
public:
/**
* Constructor.
*
* Initialize all class variables.
*/
PX4IO();
/**
* Destructor.
*
* Wait for worker thread to terminate.
*/
virtual ~PX4IO();
/**
* Initialize the PX4IO class.
*
* Initialize the physical I2C interface to PX4IO. Retrieve relevant initial system parameters. Initialize PX4IO registers.
*/
virtual int init();
/**
* IO Control handler.
*
* Handle all IOCTL calls to the PX4IO file descriptor.
*
* @param[in] filp file handle (not used). This function is always called directly through object reference
* @param[in] cmd the IOCTL command
* @param[in] the IOCTL command parameter (optional)
*/
virtual int ioctl(file *filp, int cmd, unsigned long arg);
/**
* write handler.
*
* Handle writes to the PX4IO file descriptor.
*
* @param[in] filp file handle (not used). This function is always called directly through object reference
* @param[in] buffer pointer to the data buffer to be written
* @param[in] len size in bytes to be written
* @return number of bytes written
*/
virtual ssize_t write(file *filp, const char *buffer, size_t len);
/**
* Set the update rate for actuator outputs from FMU to IO.
*
* @param rate The rate in Hz actuator outpus are sent to IO.
* @param[in] rate The rate in Hz actuator output are sent to IO.
* Min 10 Hz, max 400 Hz
*/
int set_update_rate(int rate);
@@ -111,29 +151,41 @@ public:
/**
* Set the battery current scaling and bias
*
* @param amp_per_volt
* @param amp_bias
* @param[in] amp_per_volt
* @param[in] amp_bias
*/
void set_battery_current_scaling(float amp_per_volt, float amp_bias);
/**
* Push failsafe values to IO.
*
* @param vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
* @param len Number of channels, could up to 8
* @param[in] vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
* @param[in] len Number of channels, could up to 8
*/
int set_failsafe_values(const uint16_t *vals, unsigned len);
/**
* Print the current status of IO
*/
* Print IO status.
*
* Print all relevant IO status information
*/
void print_status();
/**
* Set the DSM VCC is controlled by relay one flag
*
* @param[in] enable true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
*/
inline void set_dsm_vcc_ctl(bool enable)
{
_dsm_vcc_ctl = enable;
};
/**
* Get the DSM VCC is controlled by relay one flag
*
* @return true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
*/
inline bool get_dsm_vcc_ctl()
{
return _dsm_vcc_ctl;
@@ -141,52 +193,48 @@ public:
private:
// XXX
unsigned _max_actuators;
unsigned _max_controls;
unsigned _max_rc_input;
unsigned _max_relays;
unsigned _max_transfer;
unsigned _max_actuators; ///<Maximum # of actuators supported by PX4IO
unsigned _max_controls; ///<Maximum # of controls supported by PX4IO
unsigned _max_rc_input; ///<Maximum receiver channels supported by PX4IO
unsigned _max_relays; ///<Maximum relays supported by PX4IO
unsigned _max_transfer; ///<Maximum number of I2C transfers supported by PX4IO
unsigned _update_interval; ///< subscription interval limiting send rate
unsigned _update_interval; ///<Subscription interval limiting send rate
volatile int _task; ///< worker task
volatile bool _task_should_exit;
volatile int _task; ///<worker task id
volatile bool _task_should_exit; ///<worker terminate flag
int _mavlink_fd;
int _mavlink_fd; ///<mavlink file descriptor
perf_counter_t _perf_update;
perf_counter_t _perf_update; ///<local performance counter
/* cached IO state */
uint16_t _status;
uint16_t _alarms;
uint16_t _status; ///<Various IO status flags
uint16_t _alarms; ///<Various IO alarms
/* subscribed topics */
int _t_actuators; ///< actuator controls topic
int _t_armed; ///< system armed control topic
int _t_vstatus; ///< system / vehicle status
int _t_param; ///< parameter update topic
int _t_actuators; ///<actuator controls topic
int _t_armed; ///<system armed control topic
int _t_vstatus; ///<system / vehicle status
int _t_param; ///<parameter update topic
/* advertised topics */
orb_advert_t _to_input_rc; ///< rc inputs from io
orb_advert_t _to_actuators_effective; ///< effective actuator controls topic
orb_advert_t _to_outputs; ///< mixed servo outputs topic
orb_advert_t _to_battery; ///< battery status / voltage
orb_advert_t _to_input_rc; ///<rc inputs from IO topic
orb_advert_t _to_actuators_effective; ///<effective actuator controls topic
orb_advert_t _to_outputs; ///<mixed servo outputs topic
orb_advert_t _to_battery; ///<battery status / voltage topic
actuator_outputs_s _outputs; ///< mixed outputs
actuator_controls_effective_s _controls_effective; ///< effective controls
actuator_outputs_s _outputs; ///<mixed outputs
actuator_controls_effective_s _controls_effective; ///<effective controls
bool _primary_pwm_device; ///< true if we are the default PWM output
bool _primary_pwm_device; ///<true if we are the default PWM output
float _battery_amp_per_volt;
float _battery_amp_bias;
float _battery_mamphour_total;
uint64_t _battery_last_timestamp;
float _battery_amp_per_volt; ///<current sensor amps/volt
float _battery_amp_bias; ///<current sensor bias
float _battery_mamphour_total;///<amp hours consumed so far
uint64_t _battery_last_timestamp;///<last amp hour calculation timestamp
/**
* Relay1 is dedicated to controlling DSM receiver power
*/
bool _dsm_vcc_ctl;
bool _dsm_vcc_ctl; ///<true if relay 1 controls DSM satellite RX power
/**
* Trampoline to the worker task
@@ -570,9 +618,11 @@ void
PX4IO::task_main()
{
hrt_abstime last_poll_time = 0;
int mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
log("starting");
/*
* Subscribe to the appropriate PWM output topic based on whether we are the
* primary PWM output or not.
@@ -672,6 +722,25 @@ PX4IO::task_main()
*/
if (fds[3].revents & POLLIN) {
parameter_update_s pupdate;
int32_t dsm_bind_val;
param_t dsm_bind_param;
// See if bind parameter has been set, and reset it to 0
param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
if (dsm_bind_val) {
if (!(_status & PX4IO_P_STATUS_FLAGS_ARMED)) {
if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) {
mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x');
ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7);
} else {
mavlink_log_info(mavlink_fd, "[IO] invalid bind type, bind request rejected");
}
} else {
mavlink_log_info(mavlink_fd, "[IO] system armed, bind request rejected");
}
dsm_bind_val = 0;
param_set(dsm_bind_param, &dsm_bind_val);
}
/* copy to reset the notification */
orb_copy(ORB_ID(parameter_update), _t_param, &pupdate);
@@ -1445,16 +1514,11 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
usleep(500000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
usleep(1000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
usleep(100000);
usleep(50000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
break;
case DSM_BIND_STOP:
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
usleep(50000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
usleep(500000);
break;
case DSM_BIND_POWER_UP:
@@ -1603,7 +1667,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
}
ssize_t
PX4IO::write(file *filp, const char *buffer, size_t len)
PX4IO::write(file * /*filp*/, const char *buffer, size_t len)
/* Make it obvious that file * isn't used here */
{
unsigned count = len / 2;
@@ -1696,30 +1761,12 @@ bind(int argc, char *argv[])
else
errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]);
/* Open console directly to grab CTRL-C signal */
int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
if (!console)
errx(1, "failed opening console");
warnx("This command will only bind DSM if satellite VCC (red wire) is controlled by relay 1.");
warnx("Press CTRL-C or 'c' when done.");
g_dev->ioctl(nullptr, DSM_BIND_START, pulses);
for (;;) {
usleep(500000L);
/* Check if user wants to quit */
char c;
if (read(console, &c, 1) == 1) {
if (c == 0x03 || c == 0x63) {
warnx("Done\n");
g_dev->ioctl(nullptr, DSM_BIND_STOP, 0);
g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0);
close(console);
exit(0);
}
}
}
exit(0);
}
void
+10 -10
View File
@@ -70,7 +70,7 @@
#include "stm32_gpio.h"
#include "stm32_tim.h"
#ifdef CONFIG_HRT_TIMER
#ifdef HRT_TIMER
/* HRT configuration */
#if HRT_TIMER == 1
@@ -155,7 +155,7 @@
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
#else
# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y
# error HRT_TIMER must be a value between 1 and 11
#endif
/*
@@ -275,7 +275,7 @@ static void hrt_call_invoke(void);
/*
* Specific registers and bits used by PPM sub-functions
*/
#ifdef CONFIG_HRT_PPM
#ifdef HRT_PPM_CHANNEL
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
*
@@ -326,7 +326,7 @@ static void hrt_call_invoke(void);
# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC4P
# else
# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
# error HRT_PPM_CHANNEL must be a value between 1 and 4
# endif
/*
@@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status);
# define CCMR1_PPM 0
# define CCMR2_PPM 0
# define CCER_PPM 0
#endif /* CONFIG_HRT_PPM */
#endif /* HRT_PPM_CHANNEL */
/*
* Initialise the timer we are going to use.
@@ -424,7 +424,7 @@ hrt_tim_init(void)
up_enable_irq(HRT_TIMER_VECTOR);
}
#ifdef CONFIG_HRT_PPM
#ifdef HRT_PPM_CHANNEL
/*
* Handle the PPM decoder state machine.
*/
@@ -526,7 +526,7 @@ error:
ppm_decoded_channels = 0;
}
#endif /* CONFIG_HRT_PPM */
#endif /* HRT_PPM_CHANNEL */
/*
* Handle the compare interupt by calling the callout dispatcher
@@ -546,7 +546,7 @@ hrt_tim_isr(int irq, void *context)
/* ack the interrupts we just read */
rSR = ~status;
#ifdef CONFIG_HRT_PPM
#ifdef HRT_PPM_CHANNEL
/* was this a PPM edge? */
if (status & (SR_INT_PPM | SR_OVF_PPM)) {
@@ -686,7 +686,7 @@ hrt_init(void)
sq_init(&callout_queue);
hrt_tim_init();
#ifdef CONFIG_HRT_PPM
#ifdef HRT_PPM_CHANNEL
/* configure the PPM input pin */
stm32_configgpio(GPIO_PPM_IN);
#endif
@@ -907,4 +907,4 @@ hrt_latency_update(void)
}
#endif /* CONFIG_HRT_TIMER */
#endif /* HRT_TIMER */
+6
View File
@@ -88,6 +88,7 @@
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
static void pwm_timer_init(unsigned timer);
static void pwm_timer_set_rate(unsigned timer, unsigned rate);
@@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer)
rCCER(timer) = 0;
rDCR(timer) = 0;
if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) {
/* master output enable = on */
rBDTR(timer) = ATIM_BDTR_MOE;
}
/* configure the timer to free-run at 1MHz */
rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1;
@@ -117,10 +117,6 @@
#include <systemlib/err.h>
#ifndef CONFIG_HRT_TIMER
# error This driver requires CONFIG_HRT_TIMER
#endif
/* Tone alarm configuration */
#if TONE_ALARM_TIMER == 2
# define TONE_ALARM_BASE STM32_TIM2_BASE
@@ -47,8 +47,8 @@
#include <mathlib/mathlib.h>
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#include <controllib/block/UOrbSubscription.hpp>
#include <controllib/block/UOrbPublication.hpp>
#include <controllib/uorb/UOrbSubscription.hpp>
#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -224,8 +224,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* subscribe to raw data */
int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
/* rate-limit raw data updates to 200Hz */
orb_set_interval(sub_raw, 4);
/* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */
orb_set_interval(sub_raw, 3);
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
@@ -236,7 +236,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* advertise attitude */
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
int loopcounter = 0;
int printcounter = 0;
@@ -384,7 +383,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
static bool const_initialized = false;
/* initialize with good values once we have a reasonable dt estimate */
if (!const_initialized && dt < 0.05f && dt > 0.005f) {
if (!const_initialized && dt < 0.05f && dt > 0.001f) {
dt = 0.005f;
parameters_update(&ekf_param_handles, &ekf_params);
@@ -424,7 +423,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
if (last_data > 0 && raw.timestamp - last_data > 12000)
printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
last_data = raw.timestamp;
+2 -2
View File
@@ -43,8 +43,8 @@
#include "Block.hpp"
#include "BlockParam.hpp"
#include "UOrbSubscription.hpp"
#include "UOrbPublication.hpp"
#include "../uorb/UOrbSubscription.hpp"
#include "../uorb/UOrbPublication.hpp"
namespace control
{
+1
View File
@@ -42,6 +42,7 @@
#include <assert.h>
#include <time.h>
#include <stdlib.h>
#include <math.h>
#include <mathlib/math/test/test.hpp>
#include "block/Block.hpp"
+4 -4
View File
@@ -37,7 +37,7 @@
SRCS = test_params.c \
block/Block.cpp \
block/BlockParam.cpp \
block/UOrbPublication.cpp \
block/UOrbSubscription.cpp \
blocks.cpp \
fixedwing.cpp
uorb/UOrbPublication.cpp \
uorb/UOrbSubscription.cpp \
uorb/blocks.cpp \
blocks.cpp
@@ -39,8 +39,8 @@
#pragma once
#include <uORB/uORB.h>
#include "Block.hpp"
#include "List.hpp"
#include "../block/Block.hpp"
#include "../block/List.hpp"
namespace control
@@ -39,8 +39,8 @@
#pragma once
#include <uORB/uORB.h>
#include "Block.hpp"
#include "List.hpp"
#include "../block/Block.hpp"
#include "../block/List.hpp"
namespace control
+101
View File
@@ -0,0 +1,101 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file uorb_blocks.cpp
*
* uorb block library code
*/
#include "blocks.hpp"
namespace control
{
BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
SuperBlock(parent, name),
_xtYawLimit(this, "XT2YAW"),
_xt2Yaw(this, "XT2YAW"),
_psiCmd(0)
{
}
BlockWaypointGuidance::~BlockWaypointGuidance() {};
void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
vehicle_global_position_setpoint_s &posCmd,
vehicle_global_position_setpoint_s &lastPosCmd)
{
// heading to waypoint
float psiTrack = get_bearing_to_next_waypoint(
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
(double)posCmd.lat / (double)1e7d,
(double)posCmd.lon / (double)1e7d);
// cross track
struct crosstrack_error_s xtrackError;
get_distance_to_line(&xtrackError,
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
(double)lastPosCmd.lat / (double)1e7d,
(double)lastPosCmd.lon / (double)1e7d,
(double)posCmd.lat / (double)1e7d,
(double)posCmd.lon / (double)1e7d);
_psiCmd = _wrap_2pi(psiTrack -
_xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
}
BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
SuperBlock(parent, name),
// subscriptions
_att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
_attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
_ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
_pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
_posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
_manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
_status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
_param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
// publications
_actuators(&getPublications(), ORB_ID(actuator_controls_0))
{
}
BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {};
} // namespace control
+113
View File
@@ -0,0 +1,113 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file uorb_blocks.h
*
* uorb block library code
*/
#pragma once
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_global_position_set_triplet.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <drivers/drv_hrt.h>
#include <poll.h>
extern "C" {
#include <systemlib/geo/geo.h>
}
#include "../blocks.hpp"
#include "UOrbSubscription.hpp"
#include "UOrbPublication.hpp"
namespace control
{
/**
* Waypoint Guidance block
*/
class __EXPORT BlockWaypointGuidance : public SuperBlock
{
private:
BlockLimitSym _xtYawLimit;
BlockP _xt2Yaw;
float _psiCmd;
public:
BlockWaypointGuidance(SuperBlock *parent, const char *name);
virtual ~BlockWaypointGuidance();
void update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
vehicle_global_position_setpoint_s &posCmd,
vehicle_global_position_setpoint_s &lastPosCmd);
float getPsiCmd() { return _psiCmd; }
};
/**
* UorbEnabledAutopilot
*/
class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
{
protected:
// subscriptions
UOrbSubscription<vehicle_attitude_s> _att;
UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
UOrbSubscription<vehicle_global_position_s> _pos;
UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
UOrbSubscription<manual_control_setpoint_s> _manual;
UOrbSubscription<vehicle_status_s> _status;
UOrbSubscription<parameter_update_s> _param_update;
// publications
UOrbPublication<actuator_controls_s> _actuators;
public:
BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
virtual ~BlockUorbEnabledAutopilot();
};
} // namespace control
@@ -86,61 +86,6 @@ void BlockStabilization::update(float pCmd, float qCmd, float rCmd,
_yawDamper.update(rCmd, r, outputScale);
}
BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
SuperBlock(parent, name),
_xtYawLimit(this, "XT2YAW"),
_xt2Yaw(this, "XT2YAW"),
_psiCmd(0)
{
}
BlockWaypointGuidance::~BlockWaypointGuidance() {};
void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
vehicle_global_position_setpoint_s &posCmd,
vehicle_global_position_setpoint_s &lastPosCmd)
{
// heading to waypoint
float psiTrack = get_bearing_to_next_waypoint(
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
(double)posCmd.lat / (double)1e7d,
(double)posCmd.lon / (double)1e7d);
// cross track
struct crosstrack_error_s xtrackError;
get_distance_to_line(&xtrackError,
(double)pos.lat / (double)1e7d,
(double)pos.lon / (double)1e7d,
(double)lastPosCmd.lat / (double)1e7d,
(double)lastPosCmd.lon / (double)1e7d,
(double)posCmd.lat / (double)1e7d,
(double)posCmd.lon / (double)1e7d);
_psiCmd = _wrap_2pi(psiTrack -
_xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
}
BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
SuperBlock(parent, name),
// subscriptions
_att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
_attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
_ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
_pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
_posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
_manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
_status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
_param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
// publications
_actuators(&getPublications(), ORB_ID(actuator_controls_0))
{
}
BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {};
BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) :
BlockUorbEnabledAutopilot(parent, name),
_stabilization(this, ""), // no name needed, already unique
@@ -39,31 +39,8 @@
#pragma once
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_global_position_set_triplet.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <drivers/drv_hrt.h>
#include <poll.h>
#include "blocks.hpp"
#include "block/UOrbSubscription.hpp"
#include "block/UOrbPublication.hpp"
extern "C" {
#include <systemlib/geo/geo.h>
}
#include <controllib/blocks.hpp>
#include <controllib/uorb/blocks.hpp>
namespace control
{
@@ -250,47 +227,6 @@ public:
* than frontside at high speeds.
*/
/**
* Waypoint Guidance block
*/
class __EXPORT BlockWaypointGuidance : public SuperBlock
{
private:
BlockLimitSym _xtYawLimit;
BlockP _xt2Yaw;
float _psiCmd;
public:
BlockWaypointGuidance(SuperBlock *parent, const char *name);
virtual ~BlockWaypointGuidance();
void update(vehicle_global_position_s &pos,
vehicle_attitude_s &att,
vehicle_global_position_setpoint_s &posCmd,
vehicle_global_position_setpoint_s &lastPosCmd);
float getPsiCmd() { return _psiCmd; }
};
/**
* UorbEnabledAutopilot
*/
class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
{
protected:
// subscriptions
UOrbSubscription<vehicle_attitude_s> _att;
UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
UOrbSubscription<vehicle_global_position_s> _pos;
UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
UOrbSubscription<manual_control_setpoint_s> _manual;
UOrbSubscription<vehicle_status_s> _status;
UOrbSubscription<parameter_update_s> _param_update;
// publications
UOrbPublication<actuator_controls_s> _actuators;
public:
BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
virtual ~BlockUorbEnabledAutopilot();
};
/**
* Multi-mode Autopilot
*/
@@ -45,12 +45,13 @@
#include <stdlib.h>
#include <string.h>
#include <systemlib/systemlib.h>
#include <controllib/fixedwing.hpp>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
#include "fixedwing.hpp"
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
+1
View File
@@ -38,4 +38,5 @@
MODULE_COMMAND = fixedwing_backside
SRCS = fixedwing_backside_main.cpp \
fixedwing.cpp \
params.c
@@ -0,0 +1,77 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/// @file LowPassFilter.cpp
/// @brief A class to implement a second order low pass filter
/// Author: Leonard Hall <LeonardTHall@gmail.com>
#include "LowPassFilter2p.hpp"
#include "math.h"
namespace math
{
void LowPassFilter2p::set_cutoff_frequency(float sample_freq, float cutoff_freq)
{
_cutoff_freq = cutoff_freq;
float fr = sample_freq/_cutoff_freq;
float ohm = tanf(M_PI_F/fr);
float c = 1.0f+2.0f*cosf(M_PI_F/4.0f)*ohm + ohm*ohm;
_b0 = ohm*ohm/c;
_b1 = 2.0f*_b0;
_b2 = _b0;
_a1 = 2.0f*(ohm*ohm-1.0f)/c;
_a2 = (1.0f-2.0f*cosf(M_PI_F/4.0f)*ohm+ohm*ohm)/c;
}
float LowPassFilter2p::apply(float sample)
{
// do the filtering
float delay_element_0 = sample - _delay_element_1 * _a1 - _delay_element_2 * _a2;
if (isnan(delay_element_0) || isinf(delay_element_0)) {
// don't allow bad values to propogate via the filter
delay_element_0 = sample;
}
float output = delay_element_0 * _b0 + _delay_element_1 * _b1 + _delay_element_2 * _b2;
_delay_element_2 = _delay_element_1;
_delay_element_1 = delay_element_0;
// return the value. Should be no need to check limits
return output;
}
} // namespace math
@@ -0,0 +1,78 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/// @file LowPassFilter.h
/// @brief A class to implement a second order low pass filter
/// Author: Leonard Hall <LeonardTHall@gmail.com>
/// Adapted for PX4 by Andrew Tridgell
#pragma once
namespace math
{
class __EXPORT LowPassFilter2p
{
public:
// constructor
LowPassFilter2p(float sample_freq, float cutoff_freq) {
// set initial parameters
set_cutoff_frequency(sample_freq, cutoff_freq);
_delay_element_1 = _delay_element_2 = 0;
}
// change parameters
void set_cutoff_frequency(float sample_freq, float cutoff_freq);
// apply - Add a new raw value to the filter
// and retrieve the filtered result
float apply(float sample);
// return the cutoff frequency
float get_cutoff_freq(void) const {
return _cutoff_freq;
}
private:
float _cutoff_freq;
float _a1;
float _a2;
float _b0;
float _b1;
float _b2;
float _delay_element_1; // buffered sample -1
float _delay_element_2; // buffered sample -2
};
} // namespace math
+44
View File
@@ -0,0 +1,44 @@
############################################################################
#
# 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.
#
############################################################################
#
# filter library
#
SRCS = LowPassFilter2p.cpp
#
# In order to include .config we first have to save off the
# current makefile name, since app.mk needs it.
#
APP_MAKEFILE := $(lastword $(MAKEFILE_LIST))
-include $(TOPDIR)/.config
+2
View File
@@ -300,6 +300,8 @@ controls_tick() {
} else {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
}
} else {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
}
}
+231 -167
View File
@@ -48,156 +48,44 @@
#include <drivers/drv_hrt.h>
#define DEBUG
#include "px4io.h"
#define DSM_FRAME_SIZE 16
#define DSM_FRAME_CHANNELS 7
#define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/
#define DSM_FRAME_CHANNELS 7 /**<Max supported DSM channels*/
static int dsm_fd = -1;
static hrt_abstime last_rx_time;
static hrt_abstime last_frame_time;
static uint8_t frame[DSM_FRAME_SIZE];
static unsigned partial_frame_count;
static unsigned channel_shift;
unsigned dsm_frame_drops;
static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value);
static void dsm_guess_format(bool reset);
static bool dsm_decode(hrt_abstime now, uint16_t *values, uint16_t *num_values);
int
dsm_init(const char *device)
{
if (dsm_fd < 0)
dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
if (dsm_fd >= 0) {
struct termios t;
/* 115200bps, no parity, one stop bit */
tcgetattr(dsm_fd, &t);
cfsetspeed(&t, 115200);
t.c_cflag &= ~(CSTOPB | PARENB);
tcsetattr(dsm_fd, TCSANOW, &t);
/* initialise the decoder */
partial_frame_count = 0;
last_rx_time = hrt_absolute_time();
/* reset the format detector */
dsm_guess_format(true);
debug("DSM: ready");
} else {
debug("DSM: open failed");
}
return dsm_fd;
}
void
dsm_bind(uint16_t cmd, int pulses)
{
const uint32_t usart1RxAsOutp = GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10;
if (dsm_fd < 0)
return;
switch (cmd) {
case dsm_bind_power_down:
// power down DSM satellite
POWER_RELAY1(0);
break;
case dsm_bind_power_up:
POWER_RELAY1(1);
dsm_guess_format(true);
break;
case dsm_bind_set_rx_out:
stm32_configgpio(usart1RxAsOutp);
break;
case dsm_bind_send_pulses:
for (int i = 0; i < pulses; i++) {
stm32_gpiowrite(usart1RxAsOutp, false);
up_udelay(50);
stm32_gpiowrite(usart1RxAsOutp, true);
up_udelay(50);
}
break;
case dsm_bind_reinit_uart:
// Restore USART rx pin
stm32_configgpio(GPIO_USART1_RX);
break;
}
}
bool
dsm_input(uint16_t *values, uint16_t *num_values)
{
ssize_t ret;
hrt_abstime now;
/*
* The DSM* protocol doesn't provide any explicit framing,
* so we detect frame boundaries by the inter-frame delay.
*
* The minimum frame spacing is 11ms; with 16 bytes at 115200bps
* frame transmission time is ~1.4ms.
*
* We expect to only be called when bytes arrive for processing,
* and if an interval of more than 5ms passes between calls,
* the first byte we read will be the first byte of a frame.
*
* In the case where byte(s) are dropped from a frame, this also
* provides a degree of protection. Of course, it would be better
* if we didn't drop bytes...
*/
now = hrt_absolute_time();
if ((now - last_rx_time) > 5000) {
if (partial_frame_count > 0) {
dsm_frame_drops++;
partial_frame_count = 0;
}
}
/*
* Fetch bytes, but no more than we would need to complete
* the current frame.
*/
ret = read(dsm_fd, &frame[partial_frame_count], DSM_FRAME_SIZE - partial_frame_count);
/* if the read failed for any reason, just give up here */
if (ret < 1)
return false;
last_rx_time = now;
/*
* Add bytes to the current frame
*/
partial_frame_count += ret;
/*
* If we don't have a full frame, return
*/
if (partial_frame_count < DSM_FRAME_SIZE)
return false;
/*
* Great, it looks like we might have a frame. Go ahead and
* decode it.
*/
partial_frame_count = 0;
return dsm_decode(now, values, num_values);
}
static int dsm_fd = -1; /**<File handle to the DSM UART*/
static hrt_abstime dsm_last_rx_time; /**<Timestamp when we last received*/
static hrt_abstime dsm_last_frame_time; /**<Timestamp for start of last dsm frame*/
static uint8_t dsm_frame[DSM_FRAME_SIZE]; /**<DSM dsm frame receive buffer*/
static unsigned dsm_partial_frame_count; /**<Count of bytes received for current dsm frame*/
static unsigned dsm_channel_shift; /**<Channel resolution, 0=unknown, 1=10 bit, 2=11 bit*/
static unsigned dsm_frame_drops; /**<Count of incomplete DSM frames*/
/**
* Attempt to decode a single channel raw channel datum
*
* The DSM* protocol doesn't provide any explicit framing,
* so we detect dsm frame boundaries by the inter-dsm frame delay.
*
* The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
* dsm frame transmission time is ~1.4ms.
*
* We expect to only be called when bytes arrive for processing,
* and if an interval of more than 5ms passes between calls,
* the first byte we read will be the first byte of a dsm frame.
*
* In the case where byte(s) are dropped from a dsm frame, this also
* provides a degree of protection. Of course, it would be better
* if we didn't drop bytes...
*
* Upon receiving a full dsm frame we attempt to decode it
*
* @param[in] raw 16 bit raw channel value from dsm frame
* @param[in] shift position of channel number in raw data
* @param[out] channel pointer to returned channel number
* @param[out] value pointer to returned channel value
* @return true=raw value successfully decoded
*/
static bool
dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
{
@@ -215,6 +103,11 @@ dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *va
return true;
}
/**
* Attempt to guess if receiving 10 or 11 bit channel values
*
* @param[in] reset true=reset the 10/11 bit state to unknown
*/
static void
dsm_guess_format(bool reset)
{
@@ -227,14 +120,14 @@ dsm_guess_format(bool reset)
cs10 = 0;
cs11 = 0;
samples = 0;
channel_shift = 0;
dsm_channel_shift = 0;
return;
}
/* scan the channels in the current frame in both 10- and 11-bit mode */
/* scan the channels in the current dsm_frame in both 10- and 11-bit mode */
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
uint8_t *dp = &frame[2 + (2 * i)];
uint8_t *dp = &dsm_frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
unsigned channel, value;
@@ -245,10 +138,10 @@ dsm_guess_format(bool reset)
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
cs11 |= (1 << channel);
/* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-frame format */
/* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
}
/* wait until we have seen plenty of frames - 2 should normally be enough */
/* wait until we have seen plenty of frames - 5 should normally be enough */
if (samples++ < 5)
return;
@@ -284,13 +177,13 @@ dsm_guess_format(bool reset)
}
if ((votes11 == 1) && (votes10 == 0)) {
channel_shift = 11;
dsm_channel_shift = 11;
debug("DSM: 11-bit format");
return;
}
if ((votes10 == 1) && (votes11 == 0)) {
channel_shift = 10;
dsm_channel_shift = 10;
debug("DSM: 10-bit format");
return;
}
@@ -300,27 +193,131 @@ dsm_guess_format(bool reset)
dsm_guess_format(true);
}
/**
* Initialize the DSM receive functionality
*
* Open the UART for receiving DSM frames and configure it appropriately
*
* @param[in] device Device name of DSM UART
*/
int
dsm_init(const char *device)
{
if (dsm_fd < 0)
dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
if (dsm_fd >= 0) {
struct termios t;
/* 115200bps, no parity, one stop bit */
tcgetattr(dsm_fd, &t);
cfsetspeed(&t, 115200);
t.c_cflag &= ~(CSTOPB | PARENB);
tcsetattr(dsm_fd, TCSANOW, &t);
/* initialise the decoder */
dsm_partial_frame_count = 0;
dsm_last_rx_time = hrt_absolute_time();
/* reset the format detector */
dsm_guess_format(true);
debug("DSM: ready");
} else {
debug("DSM: open failed");
}
return dsm_fd;
}
/**
* Handle DSM satellite receiver bind mode handler
*
* @param[in] cmd commands - dsm_bind_power_down, dsm_bind_power_up, dsm_bind_set_rx_out, dsm_bind_send_pulses, dsm_bind_reinit_uart
* @param[in] pulses Number of pulses for dsm_bind_send_pulses command
*/
void
dsm_bind(uint16_t cmd, int pulses)
{
const uint32_t usart1RxAsOutp =
GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN10;
if (dsm_fd < 0)
return;
switch (cmd) {
case dsm_bind_power_down:
/*power down DSM satellite*/
POWER_RELAY1(0);
break;
case dsm_bind_power_up:
/*power up DSM satellite*/
POWER_RELAY1(1);
dsm_guess_format(true);
break;
case dsm_bind_set_rx_out:
/*Set UART RX pin to active output mode*/
stm32_configgpio(usart1RxAsOutp);
break;
case dsm_bind_send_pulses:
/*Pulse RX pin a number of times*/
for (int i = 0; i < pulses; i++) {
stm32_gpiowrite(usart1RxAsOutp, false);
up_udelay(25);
stm32_gpiowrite(usart1RxAsOutp, true);
up_udelay(25);
}
break;
case dsm_bind_reinit_uart:
/*Restore USART RX pin to RS232 receive mode*/
stm32_configgpio(GPIO_USART1_RX);
break;
}
}
/**
* Decode the entire dsm frame (all contained channels)
*
* @param[in] frame_time timestamp when this dsm frame was received. Used to detect RX loss in order to reset 10/11 bit guess.
* @param[out] values pointer to per channel array of decoded values
* @param[out] num_values pointer to number of raw channel values returned
* @return true=DSM frame successfully decoded, false=no update
*/
static bool
dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
{
/*
debug("DSM frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
frame[0], frame[1], frame[2], frame[3], frame[4], frame[5], frame[6], frame[7],
frame[8], frame[9], frame[10], frame[11], frame[12], frame[13], frame[14], frame[15]);
debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7],
dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]);
*/
/*
* If we have lost signal for at least a second, reset the
* format guessing heuristic.
*/
if (((frame_time - last_frame_time) > 1000000) && (channel_shift != 0))
if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
dsm_guess_format(true);
/* we have received something we think is a frame */
last_frame_time = frame_time;
/* we have received something we think is a dsm_frame */
dsm_last_frame_time = frame_time;
/* if we don't know the frame format, update the guessing state machine */
if (channel_shift == 0) {
/* if we don't know the dsm_frame format, update the guessing state machine */
if (dsm_channel_shift == 0) {
dsm_guess_format(false);
return false;
}
@@ -332,17 +329,17 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
* Each channel is a 16-bit unsigned value containing either a 10-
* or 11-bit channel value and a 4-bit channel number, shifted
* either 10 or 11 bits. The MSB may also be set to indicate the
* second frame in variants of the protocol where more than
* second dsm_frame in variants of the protocol where more than
* seven channels are being transmitted.
*/
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
uint8_t *dp = &frame[2 + (2 * i)];
uint8_t *dp = &dsm_frame[2 + (2 * i)];
uint16_t raw = (dp[0] << 8) | dp[1];
unsigned channel, value;
if (!dsm_decode_channel(raw, channel_shift, &channel, &value))
if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
continue;
/* ignore channels out of range */
@@ -354,7 +351,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
*num_values = channel + 1;
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
if (channel_shift == 11)
if (dsm_channel_shift == 11)
value /= 2;
value += 998;
@@ -385,7 +382,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
values[channel] = value;
}
if (channel_shift == 11)
if (dsm_channel_shift == 11)
*num_values |= 0x8000;
/*
@@ -393,3 +390,70 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
*/
return true;
}
/**
* Called periodically to check for input data from the DSM UART
*
* The DSM* protocol doesn't provide any explicit framing,
* so we detect dsm frame boundaries by the inter-dsm frame delay.
* The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
* dsm frame transmission time is ~1.4ms.
* We expect to only be called when bytes arrive for processing,
* and if an interval of more than 5ms passes between calls,
* the first byte we read will be the first byte of a dsm frame.
* In the case where byte(s) are dropped from a dsm frame, this also
* provides a degree of protection. Of course, it would be better
* if we didn't drop bytes...
* Upon receiving a full dsm frame we attempt to decode it.
*
* @param[out] values pointer to per channel array of decoded values
* @param[out] num_values pointer to number of raw channel values returned
* @return true=decoded raw channel values updated, false=no update
*/
bool
dsm_input(uint16_t *values, uint16_t *num_values)
{
ssize_t ret;
hrt_abstime now;
/*
*/
now = hrt_absolute_time();
if ((now - dsm_last_rx_time) > 5000) {
if (dsm_partial_frame_count > 0) {
dsm_frame_drops++;
dsm_partial_frame_count = 0;
}
}
/*
* Fetch bytes, but no more than we would need to complete
* the current dsm frame.
*/
ret = read(dsm_fd, &dsm_frame[dsm_partial_frame_count], DSM_FRAME_SIZE - dsm_partial_frame_count);
/* if the read failed for any reason, just give up here */
if (ret < 1)
return false;
dsm_last_rx_time = now;
/*
* Add bytes to the current dsm frame
*/
dsm_partial_frame_count += ret;
/*
* If we don't have a full dsm frame, return
*/
if (dsm_partial_frame_count < DSM_FRAME_SIZE)
return false;
/*
* Great, it looks like we might have a dsm frame. Go ahead and
* decode it.
*/
dsm_partial_frame_count = 0;
return dsm_decode(now, values, num_values);
}
+4 -4
View File
@@ -184,7 +184,7 @@ extern void controls_init(void);
extern void controls_tick(void);
extern int dsm_init(const char *device);
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
extern void dsm_bind(uint16_t cmd, int pulses);
extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
extern bool sbus_input(uint16_t *values, uint16_t *num_values);
@@ -192,9 +192,9 @@ extern bool sbus_input(uint16_t *values, uint16_t *num_values);
extern volatile uint8_t debug_level;
/* send a debug message to the console */
extern void isr_debug(uint8_t level, const char *fmt, ...);
extern void isr_debug(uint8_t level, const char *fmt, ...);
#ifdef CONFIG_STM32_I2C1
void i2c_dump(void);
void i2c_reset(void);
void i2c_dump(void);
void i2c_reset(void);
#endif
+10 -1
View File
@@ -604,6 +604,15 @@ int sdlog2_thread_main(int argc, char *argv[])
errx(1, "unable to create logging folder, exiting.");
}
const char *converter_in = "/etc/logging/conv.zip";
char* converter_out = malloc(150);
sprintf(converter_out, "%s/conv.zip", folder_path);
if (file_copy(converter_in, converter_out)) {
errx(1, "unable to copy conversion scripts, exiting.");
}
free(converter_out);
/* only print logging path, important to find log file later */
warnx("logging to directory: %s", folder_path);
@@ -1256,7 +1265,7 @@ int file_copy(const char *file_old, const char *file_new)
fclose(source);
fclose(target);
return ret;
return OK;
}
void handle_command(struct vehicle_command_s *cmd)
@@ -0,0 +1,57 @@
#include "BlockSegwayController.hpp"
void BlockSegwayController::update() {
// wait for a sensor update, check for exit condition every 100 ms
if (poll(&_attPoll, 1, 100) < 0) return; // poll error
uint64_t newTimeStamp = hrt_absolute_time();
float dt = (newTimeStamp - _timeStamp) / 1.0e6f;
_timeStamp = newTimeStamp;
// check for sane values of dt
// to prevent large control responses
if (dt > 1.0f || dt < 0) return;
// set dt for all child blocks
setDt(dt);
// check for new updates
if (_param_update.updated()) updateParams();
// get new information from subscriptions
updateSubscriptions();
// default all output to zero unless handled by mode
for (unsigned i = 2; i < NUM_ACTUATOR_CONTROLS; i++)
_actuators.control[i] = 0.0f;
// only update guidance in auto mode
if (_status.state_machine == SYSTEM_STATE_AUTO) {
// update guidance
}
// compute speed command
float spdCmd = -th2v.update(_att.pitch) - q2v.update(_att.pitchspeed);
// handle autopilot modes
if (_status.state_machine == SYSTEM_STATE_AUTO ||
_status.state_machine == SYSTEM_STATE_STABILIZED) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
} else if (_status.state_machine == SYSTEM_STATE_MANUAL) {
if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
_actuators.control[CH_LEFT] = _manual.throttle;
_actuators.control[CH_RIGHT] = _manual.pitch;
} else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
}
}
// update all publications
updatePublications();
}
@@ -0,0 +1,27 @@
#pragma once
#include <controllib/uorb/blocks.hpp>
using namespace control;
class BlockSegwayController : public control::BlockUorbEnabledAutopilot {
public:
BlockSegwayController() :
BlockUorbEnabledAutopilot(NULL,"SEG"),
th2v(this, "TH2V"),
q2v(this, "Q2V"),
_attPoll(),
_timeStamp(0)
{
_attPoll.fd = _att.getHandle();
_attPoll.events = POLLIN;
}
void update();
private:
enum {CH_LEFT, CH_RIGHT};
BlockPI th2v;
BlockP q2v;
struct pollfd _attPoll;
uint64_t _timeStamp;
};
+42
View File
@@ -0,0 +1,42 @@
############################################################################
#
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# segway controller
#
MODULE_COMMAND = segway
SRCS = segway_main.cpp \
BlockSegwayController.cpp \
params.c
+8
View File
@@ -0,0 +1,8 @@
#include <systemlib/param/param.h>
// 16 is max name length
PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage
PARAM_DEFINE_FLOAT(SEG_TH2V_I, 0.0f); // pitch integral to voltage
PARAM_DEFINE_FLOAT(SEG_TH2V_I_MAX, 0.0f); // integral limiter
PARAM_DEFINE_FLOAT(SEG_Q2V, 1.0f); // pitch rate to voltage
+157
View File
@@ -0,0 +1,157 @@
/****************************************************************************
*
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* Author: James Goppert
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file segway_main.cpp
* @author James Goppert
*
* Segway controller using control library
*/
#include <nuttx/config.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
#include "BlockSegwayController.hpp"
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
/**
* Deamon management function.
*/
extern "C" __EXPORT int segway_main(int argc, char *argv[]);
/**
* Mainloop of deamon.
*/
int segway_thread_main(int argc, char *argv[]);
/**
* Print the correct usage.
*/
static void usage(const char *reason);
static void
usage(const char *reason)
{
if (reason)
fprintf(stderr, "%s\n", reason);
fprintf(stderr, "usage: segway {start|stop|status} [-p <additional params>]\n\n");
exit(1);
}
/**
* The deamon app only briefly exists to start
* the background job. The stack size assigned in the
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
* to task_create().
*/
int segway_main(int argc, char *argv[])
{
if (argc < 1)
usage("missing command");
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("already running");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
deamon_task = task_spawn_cmd("segway",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
segway_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
}
if (!strcmp(argv[1], "stop")) {
thread_should_exit = true;
exit(0);
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("is running");
} else {
warnx("not started");
}
exit(0);
}
usage("unrecognized command");
exit(1);
}
int segway_thread_main(int argc, char *argv[])
{
warnx("starting");
using namespace control;
BlockSegwayController autopilot;
thread_running = true;
while (!thread_should_exit) {
autopilot.update();
}
warnx("exiting.");
thread_running = false;
return 0;
}
+1
View File
@@ -156,6 +156,7 @@ PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f));
+73 -23
View File
@@ -92,8 +92,35 @@
#define BARO_HEALTH_COUNTER_LIMIT_OK 5
#define ADC_HEALTH_COUNTER_LIMIT_OK 5
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
/**
* Analog layout:
* FMU:
* IN2 - battery voltage
* IN3 - battery current
* IN4 - 5V sense
* IN10 - spare (we could actually trim these from the set)
* IN11 - spare (we could actually trim these from the set)
* IN12 - spare (we could actually trim these from the set)
* IN13 - aux1
* IN14 - aux2
* IN15 - pressure sensor
*
* IO:
* IN4 - servo supply rail
* IN5 - analog RSSI
*/
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
#endif
#define BAT_VOL_INITIAL 0.f
#define BAT_VOL_LOWPASS_1 0.99f
@@ -230,8 +257,6 @@ private:
float battery_voltage_scaling;
int rc_rl1_DSM_VCC_control;
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -281,8 +306,6 @@ private:
param_t battery_voltage_scaling;
param_t rc_rl1_DSM_VCC_control;
} _parameter_handles; /**< handles for interesting parameters */
@@ -517,9 +540,6 @@ Sensors::Sensors() :
_parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING");
/* DSM VCC relay control */
_parameter_handles.rc_rl1_DSM_VCC_control = param_find("RC_RL1_DSM_VCC");
/* fetch initial parameter values */
parameters_update();
}
@@ -711,11 +731,6 @@ Sensors::parameters_update()
warnx("Failed updating voltage scaling param");
}
/* relay 1 DSM VCC control */
if (param_get(_parameter_handles.rc_rl1_DSM_VCC_control, &(_parameters.rc_rl1_DSM_VCC_control)) != OK) {
warnx("Failed updating relay 1 DSM VCC control");
}
return OK;
}
@@ -731,11 +746,26 @@ Sensors::accel_init()
errx(1, "FATAL: no accelerometer found");
} else {
/* set the accel internal sampling rate up to at leat 500Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 500);
/* set the driver to poll at 500Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 500);
// XXX do the check more elegantly
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the accel internal sampling rate up to at leat 1000Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 1000);
/* set the driver to poll at 1000Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 1000);
#else
/* set the accel internal sampling rate up to at leat 800Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 800);
/* set the driver to poll at 800Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 800);
#endif
warnx("using system accel");
close(fd);
@@ -754,11 +784,28 @@ Sensors::gyro_init()
errx(1, "FATAL: no gyro found");
} else {
/* set the gyro internal sampling rate up to at leat 500Hz */
ioctl(fd, GYROIOCSSAMPLERATE, 500);
/* set the driver to poll at 500Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 500);
// XXX do the check more elegantly
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the gyro internal sampling rate up to at least 1000Hz */
if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
ioctl(fd, GYROIOCSSAMPLERATE, 800);
/* set the driver to poll at 1000Hz */
if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
ioctl(fd, SENSORIOCSPOLLRATE, 800);
#else
/* set the gyro internal sampling rate up to at leat 800Hz */
ioctl(fd, GYROIOCSSAMPLERATE, 800);
/* set the driver to poll at 800Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 800);
#endif
warnx("using system gyro");
close(fd);
@@ -1360,6 +1407,9 @@ Sensors::task_main()
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vstatus_sub, 200);
/* rate limit gyro to 250 Hz (the gyro signal is lowpassed accordingly earlier) */
orb_set_interval(_gyro_sub, 4);
/*
* do advertisements
*/
@@ -1395,7 +1445,7 @@ Sensors::task_main()
while (!_task_should_exit) {
/* wait for up to 500ms for data */
/* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
+126 -65
View File
@@ -53,14 +53,26 @@
struct hx_stream {
uint8_t buf[HX_STREAM_MAX_FRAME + 4];
unsigned frame_bytes;
bool escaped;
bool txerror;
/* RX state */
uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4];
unsigned rx_frame_bytes;
bool rx_escaped;
hx_stream_rx_callback rx_callback;
void *rx_callback_arg;
/* TX state */
int fd;
hx_stream_rx_callback callback;
void *callback_arg;
bool tx_error;
uint8_t *tx_buf;
unsigned tx_resid;
uint32_t tx_crc;
enum {
TX_IDLE = 0,
TX_SEND_START,
TX_SEND_DATA,
TX_SENT_ESCAPE,
TX_SEND_END
} tx_state;
perf_counter_t pc_tx_frames;
perf_counter_t pc_rx_frames;
@@ -81,21 +93,7 @@ static void
hx_tx_raw(hx_stream_t stream, uint8_t c)
{
if (write(stream->fd, &c, 1) != 1)
stream->txerror = true;
}
static void
hx_tx_byte(hx_stream_t stream, uint8_t c)
{
switch (c) {
case FBO:
case CEO:
hx_tx_raw(stream, CEO);
c ^= 0x20;
break;
}
hx_tx_raw(stream, c);
stream->tx_error = true;
}
static int
@@ -105,11 +103,11 @@ hx_rx_frame(hx_stream_t stream)
uint8_t b[4];
uint32_t w;
} u;
unsigned length = stream->frame_bytes;
unsigned length = stream->rx_frame_bytes;
/* reset the stream */
stream->frame_bytes = 0;
stream->escaped = false;
stream->rx_frame_bytes = 0;
stream->rx_escaped = false;
/* not a real frame - too short */
if (length < 4) {
@@ -122,11 +120,11 @@ hx_rx_frame(hx_stream_t stream)
length -= 4;
/* compute expected CRC */
u.w = crc32(&stream->buf[0], length);
u.w = crc32(&stream->rx_buf[0], length);
/* compare computed and actual CRC */
for (unsigned i = 0; i < 4; i++) {
if (u.b[i] != stream->buf[length + i]) {
if (u.b[i] != stream->rx_buf[length + i]) {
perf_count(stream->pc_rx_errors);
return 0;
}
@@ -134,7 +132,7 @@ hx_rx_frame(hx_stream_t stream)
/* frame is good */
perf_count(stream->pc_rx_frames);
stream->callback(stream->callback_arg, &stream->buf[0], length);
stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length);
return 1;
}
@@ -150,8 +148,8 @@ hx_stream_init(int fd,
if (stream != NULL) {
memset(stream, 0, sizeof(struct hx_stream));
stream->fd = fd;
stream->callback = callback;
stream->callback_arg = arg;
stream->rx_callback = callback;
stream->rx_callback_arg = arg;
}
return stream;
@@ -179,49 +177,112 @@ hx_stream_set_counters(hx_stream_t stream,
stream->pc_rx_errors = rx_errors;
}
void
hx_stream_reset(hx_stream_t stream)
{
stream->rx_frame_bytes = 0;
stream->rx_escaped = false;
stream->tx_buf = NULL;
stream->tx_resid = 0;
stream->tx_state = TX_IDLE;
}
int
hx_stream_start(hx_stream_t stream,
const void *data,
size_t count)
{
if (count > HX_STREAM_MAX_FRAME)
return -EINVAL;
stream->tx_buf = data;
stream->tx_resid = count;
stream->tx_state = TX_SEND_START;
stream->tx_crc = crc32(data, count);
return OK;
}
int
hx_stream_send_next(hx_stream_t stream)
{
int c;
/* sort out what we're going to send */
switch (stream->tx_state) {
case TX_SEND_START:
stream->tx_state = TX_SEND_DATA;
return FBO;
case TX_SEND_DATA:
c = *stream->tx_buf;
switch (c) {
case FBO:
case CEO:
stream->tx_state = TX_SENT_ESCAPE;
return CEO;
}
break;
case TX_SENT_ESCAPE:
c = *stream->tx_buf ^ 0x20;
stream->tx_state = TX_SEND_DATA;
break;
case TX_SEND_END:
stream->tx_state = TX_IDLE;
return FBO;
case TX_IDLE:
default:
return -1;
}
/* if we are here, we have consumed a byte from the buffer */
stream->tx_resid--;
stream->tx_buf++;
/* buffer exhausted */
if (stream->tx_resid == 0) {
uint8_t *pcrc = (uint8_t *)&stream->tx_crc;
/* was the buffer the frame CRC? */
if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) {
stream->tx_state = TX_SEND_END;
} else {
/* no, it was the payload - switch to sending the CRC */
stream->tx_buf = pcrc;
stream->tx_resid = sizeof(stream->tx_crc);
}
}
return c;
}
int
hx_stream_send(hx_stream_t stream,
const void *data,
size_t count)
{
union {
uint8_t b[4];
uint32_t w;
} u;
const uint8_t *p = (const uint8_t *)data;
unsigned resid = count;
int result;
if (resid > HX_STREAM_MAX_FRAME)
return -EINVAL;
result = hx_stream_start(stream, data, count);
if (result != OK)
return result;
/* start the frame */
hx_tx_raw(stream, FBO);
/* transmit the data */
while (resid--)
hx_tx_byte(stream, *p++);
/* compute the CRC */
u.w = crc32(data, count);
/* send the CRC */
p = &u.b[0];
resid = 4;
while (resid--)
hx_tx_byte(stream, *p++);
/* and the trailing frame separator */
hx_tx_raw(stream, FBO);
int c;
while ((c = hx_stream_send_next(stream)) >= 0)
hx_tx_raw(stream, c);
/* check for transmit error */
if (stream->txerror) {
stream->txerror = false;
if (stream->tx_error) {
stream->tx_error = false;
return -EIO;
}
perf_count(stream->pc_tx_frames);
return 0;
return OK;
}
void
@@ -234,17 +295,17 @@ hx_stream_rx(hx_stream_t stream, uint8_t c)
}
/* escaped? */
if (stream->escaped) {
stream->escaped = false;
if (stream->rx_escaped) {
stream->rx_escaped = false;
c ^= 0x20;
} else if (c == CEO) {
/* now escaped, ignore the byte */
stream->escaped = true;
/* now rx_escaped, ignore the byte */
stream->rx_escaped = true;
return;
}
/* save for later */
if (stream->frame_bytes < sizeof(stream->buf))
stream->buf[stream->frame_bytes++] = c;
if (stream->rx_frame_bytes < sizeof(stream->rx_buf))
stream->rx_buf[stream->rx_frame_bytes++] = c;
}
+41 -1
View File
@@ -58,7 +58,8 @@ __BEGIN_DECLS
* Allocate a new hx_stream object.
*
* @param fd The file handle over which the protocol will
* communicate.
* communicate, or -1 if the protocol will use
* hx_stream_start/hx_stream_send_next.
* @param callback Called when a frame is received.
* @param callback_arg Passed to the callback.
* @return A handle to the stream, or NULL if memory could
@@ -80,6 +81,7 @@ __EXPORT extern void hx_stream_free(hx_stream_t stream);
*
* Any counter may be set to NULL to disable counting that datum.
*
* @param stream A handle returned from hx_stream_init.
* @param tx_frames Counter for transmitted frames.
* @param rx_frames Counter for received frames.
* @param rx_errors Counter for short and corrupt received frames.
@@ -89,6 +91,44 @@ __EXPORT extern void hx_stream_set_counters(hx_stream_t stream,
perf_counter_t rx_frames,
perf_counter_t rx_errors);
/**
* Reset a stream.
*
* Forces the local stream state to idle.
*
* @param stream A handle returned from hx_stream_init.
*/
__EXPORT extern void hx_stream_reset(hx_stream_t stream);
/**
* Prepare to send a frame.
*
* Use this in conjunction with hx_stream_send_next to
* set the frame to be transmitted.
*
* Use hx_stream_send() to write to the stream fd directly.
*
* @param stream A handle returned from hx_stream_init.
* @param data Pointer to the data to send.
* @param count The number of bytes to send.
* @return Zero on success, -errno on error.
*/
__EXPORT extern int hx_stream_start(hx_stream_t stream,
const void *data,
size_t count);
/**
* Get the next byte to send for a stream.
*
* This requires that the stream be prepared for sending by
* calling hx_stream_start first.
*
* @param stream A handle returned from hx_stream_init.
* @return The byte to send, or -1 if there is
* nothing left to send.
*/
__EXPORT extern int hx_stream_send_next(hx_stream_t stream);
/**
* Send a frame.
*
+34 -7
View File
@@ -201,23 +201,50 @@ perf_end(perf_counter_t handle)
switch (handle->type) {
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
pce->event_count++;
pce->time_total += elapsed;
if (pce->time_start != 0) {
hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
if ((pce->time_least > elapsed) || (pce->time_least == 0))
pce->time_least = elapsed;
pce->event_count++;
pce->time_total += elapsed;
if (pce->time_most < elapsed)
pce->time_most = elapsed;
if ((pce->time_least > elapsed) || (pce->time_least == 0))
pce->time_least = elapsed;
if (pce->time_most < elapsed)
pce->time_most = elapsed;
pce->time_start = 0;
}
}
break;
default:
break;
}
}
void
perf_cancel(perf_counter_t handle)
{
if (handle == NULL)
return;
switch (handle->type) {
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
pce->time_start = 0;
}
break;
default:
break;
}
}
void
perf_reset(perf_counter_t handle)
{
+13 -1
View File
@@ -92,13 +92,25 @@ __EXPORT extern void perf_begin(perf_counter_t handle);
* End a performance event.
*
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
* If a call is made without a corresopnding perf_begin call, or if perf_cancel
* has been called subsequently, no change is made to the counter.
*
* @param handle The handle returned from perf_alloc.
*/
__EXPORT extern void perf_end(perf_counter_t handle);
/**
* Reset a performance event.
* Cancel a performance event.
*
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
* It reverts the effect of a previous perf_begin.
*
* @param handle The handle returned from perf_alloc.
*/
__EXPORT extern void perf_cancel(perf_counter_t handle);
/**
* Reset a performance counter.
*
* This call resets performance counter to initial state
*
+4
View File
@@ -37,6 +37,10 @@
* Common object definitions without a better home.
*/
/**
* @defgroup topics List of all uORB topics.
*/
#include <nuttx/config.h>
#include <drivers/drv_orb_dev.h>
@@ -52,11 +52,20 @@
#define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
/**
* @addtogroup topics
* @{
*/
struct actuator_controls_s {
uint64_t timestamp;
float control[NUM_ACTUATOR_CONTROLS];
};
/**
* @}
*/
/* actuator control sets; this list can be expanded as more controllers emerge */
ORB_DECLARE(actuator_controls_0);
ORB_DECLARE(actuator_controls_1);
@@ -53,11 +53,20 @@
#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
/**
* @addtogroup topics
* @{
*/
struct actuator_controls_effective_s {
uint64_t timestamp;
float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
};
/**
* @}
*/
/* actuator control sets; this list can be expanded as more controllers emerge */
ORB_DECLARE(actuator_controls_effective_0);
ORB_DECLARE(actuator_controls_effective_1);
@@ -52,12 +52,21 @@
#define NUM_ACTUATOR_OUTPUTS 16
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
/**
* @addtogroup topics
* @{
*/
struct actuator_outputs_s {
uint64_t timestamp; /**< output timestamp in us since system boot */
float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */
int noutputs; /**< valid outputs */
};
/**
* @}
*/
/* actuator output sets; this list can be expanded as more drivers emerge */
ORB_DECLARE(actuator_outputs_0);
ORB_DECLARE(actuator_outputs_1);
@@ -47,6 +47,7 @@
/**
* @addtogroup topics
* @{
*/
/**

Some files were not shown because too many files have changed in this diff Show More