aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDoug Weibel <deweibel@gmail.com>2012-10-21 14:27:36 -0600
committerDoug Weibel <deweibel@gmail.com>2012-10-21 14:27:36 -0600
commit64ba024db229a0e64f95a104a822670663a3763d (patch)
treee081299a68f74195034e67c0f9ec3a37f7941107
parent0a0215338a4bd6550805072d036c6cb396e7497a (diff)
parent73521cbc66fa4fbc350c15cef277fabfce89c150 (diff)
downloadpx4-firmware-64ba024db229a0e64f95a104a822670663a3763d.tar.gz
px4-firmware-64ba024db229a0e64f95a104a822670663a3763d.tar.bz2
px4-firmware-64ba024db229a0e64f95a104a822670663a3763d.zip
Merge branch 'master' of https://github.com/PX4/Firmware
-rw-r--r--.gitignore1
-rw-r--r--apps/ChangeLog.txt29
-rw-r--r--apps/Kconfig4
-rw-r--r--apps/Makefile9
-rw-r--r--apps/README.txt2
-rw-r--r--apps/drivers/device/cdev.cpp4
-rw-r--r--apps/drivers/device/device.h6
-rw-r--r--apps/examples/Make.defs6
-rw-r--r--apps/examples/README.txt114
-rw-r--r--apps/examples/adc/Kconfig24
-rw-r--r--apps/examples/adc/adc_main.c14
-rw-r--r--apps/examples/buttons/Kconfig52
-rw-r--r--apps/examples/buttons/buttons_main.c88
-rw-r--r--apps/examples/poll/net_listener.c10
-rw-r--r--apps/examples/poll/net_reader.c10
-rw-r--r--apps/nshlib/Kconfig58
-rw-r--r--apps/nshlib/nsh.h35
-rw-r--r--apps/nshlib/nsh_console.c15
-rw-r--r--apps/nshlib/nsh_console.h2
-rw-r--r--apps/nshlib/nsh_parse.c11
-rw-r--r--apps/nshlib/nsh_telnetd.c110
-rw-r--r--apps/px4/fmu/fmu.cpp51
-rw-r--r--apps/px4/px4io/driver/px4io.cpp549
-rw-r--r--apps/px4/px4io/driver/uploader.cpp2
-rw-r--r--apps/px4/tests/test_sensors.c330
-rw-r--r--apps/px4io/protocol.h2
-rw-r--r--apps/system/Kconfig20
-rw-r--r--apps/system/Make.defs17
-rw-r--r--apps/system/Makefile2
-rw-r--r--apps/system/free/free.c80
-rw-r--r--apps/system/i2c/Makefile2
-rw-r--r--apps/system/install/install.c606
-rw-r--r--apps/system/readline/readline.c2
-rw-r--r--apps/systemcmds/top/top.c25
-rw-r--r--nuttx/ChangeLog79
-rw-r--r--nuttx/README.txt5
-rw-r--r--nuttx/ReleaseNotes108
-rw-r--r--nuttx/TODO50
-rw-r--r--nuttx/arch/arm/src/armv7-m/nvic.h18
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_systemreset.c (renamed from nuttx/configs/px4fmu/include/drv_lis331.h)82
-rw-r--r--nuttx/arch/arm/src/common/up_initialize.c6
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h10
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig2
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs10
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_rng.h77
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_eth.c82
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_gpio.c1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rng.c264
-rw-r--r--nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld (renamed from nuttx/binfmt/libnxflat/gnu-nxflat.ld)21
-rw-r--r--nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld187
-rw-r--r--nuttx/configs/Kconfig1
-rw-r--r--nuttx/configs/README.txt24
-rw-r--r--nuttx/configs/px4fmu/common/Make.defs18
-rw-r--r--nuttx/configs/px4fmu/include/drv_bma180.h99
-rw-r--r--nuttx/configs/px4fmu/include/drv_hmc5883l.h100
-rw-r--r--nuttx/configs/px4fmu/include/drv_l3gd20.h108
-rw-r--r--nuttx/configs/px4fmu/include/drv_ms5611.h76
-rw-r--r--nuttx/configs/px4fmu/src/Makefile2
-rw-r--r--nuttx/configs/px4fmu/src/drv_bma180.c341
-rw-r--r--nuttx/configs/px4fmu/src/drv_hmc5833l.c386
-rw-r--r--nuttx/configs/px4fmu/src/drv_l3gd20.c364
-rw-r--r--nuttx/configs/px4fmu/src/drv_lis331.c272
-rw-r--r--nuttx/configs/px4fmu/src/drv_ms5611.c504
-rw-r--r--nuttx/configs/px4fmu/src/up_nsh.c31
-rwxr-xr-xnuttx/configs/px4io/common/setenv.sh2
-rwxr-xr-xnuttx/configs/px4io/io/setenv.sh2
-rw-r--r--nuttx/drivers/Kconfig8
-rw-r--r--nuttx/drivers/input/Kconfig191
-rw-r--r--nuttx/drivers/input/ads7843e.c224
-rw-r--r--nuttx/drivers/input/ads7843e.h2
-rw-r--r--nuttx/drivers/lcd/ssd1289.c123
-rw-r--r--nuttx/drivers/mtd/ramtron.c220
-rw-r--r--nuttx/drivers/mtd/w25.c21
-rw-r--r--nuttx/fs/nxffs/Kconfig16
-rw-r--r--nuttx/include/nuttx/input/ads7843e.h14
-rw-r--r--nuttx/include/nuttx/input/stmpe811.h2
-rw-r--r--nuttx/lib/stdio/lib_libvsprintf.c8
-rw-r--r--nuttx/net/Kconfig6
-rw-r--r--nuttx/net/uip/uip_icmpping.c157
79 files changed, 2874 insertions, 3742 deletions
diff --git a/.gitignore b/.gitignore
index 40957d3fb..b5bd27d53 100644
--- a/.gitignore
+++ b/.gitignore
@@ -38,3 +38,4 @@ Firmware.sublime-workspace
nsh_romfsimg.h
cscope.out
.configX-e
+nuttx-export.zip
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index d24494f54..7375adccf 100644
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -279,14 +279,14 @@
* apps/*/Make.defs: Numerous fixes needed to use the automated
configuration (from Richard Cochran).
-6.22 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+6.22 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
* apps/netutils/thttpd/thttpd_cgi.c: Missing NULL in argv[]
list (contributed by Kate).
* apps/nshlib/nsh_parse.c: CONFIG_NSH_DISABLE_WGET not CONFIG_NSH_DISABLE_GET
in one location (found by Kate).
* apps/examples/ostest/prioinherit.c: Limit the number of test
- threds to no more than 3 of each priority. Bad things happen
+ threads to no more than 3 of each priority. Bad things happen
when the existing logic tried to created several hundred test
treads!
* apps/nshlib/nsh.h: Both CONFIG_LIBC_STRERROR and CONFIG_NSH_STRERROR
@@ -341,7 +341,30 @@
* apps/netutils/webserver/httpd.c: Add support for Keep-alive connections
(from Kate).
* apps/NxWidget/Kconfig: This is a kludge. I created this NxWidgets
- directory that ONLY contains Kconfig. NxWidgets does not like in
+ directory that ONLY contains Kconfig. NxWidgets does not live in
either the nuttx/ or the apps/ source trees. This kludge makes it
possible to configure NxWidgets/NxWM without too much trouble (with
the tradeoff being a kind ugly structure and some maintenance issues).
+ * apps/examples/Make.defs: Missing support for apps/examples/watchdog.
+ * apps/NxWidgets/Kconfig: Add option to turn on the memory monitor
+ feature of the NxWidgets/NxWM unit tests.
+
+6.23 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+
+ * vsn: Moved all NSH commands from vsn/ to system/. Deleted the vsn/
+ directory.
+ * Makefile: Change order of includes when CONFIG_NEWCONFIG=y. In
+ that case, namedapp must be included first so that the namedapp
+ context is established first. If the namedapp context is established
+ later, it will overwrite any existing namedapp_list.h and nameapp_proto.h
+ files.
+ * CONFIG_EXAMPLES_*: To make things consistent, changed all occurrences
+ of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*.
+ * Kconfig: Fleshed out apps/examples/adc/Kconfig and apps/examples/wget/Kconfig.
+ There are still a LOT of empty, stub Kconfig files.
+ * Kconfig: Fleshed out apps/examples/buttons/Kconfig. There are still a LOT
+ of empty, stub Kconfig files.
+ * apps/netutils/webserver/httpd.c: Fix a bug that I introduced in
+ recent check-ins (Darcy Gong).
+ * apps/netutils/webclient/webclient.c: Fix another but that I introduced
+ when I was trying to add correct handling for loss of connection (Darcy Gong)
diff --git a/apps/Kconfig b/apps/Kconfig
index 5543ba72d..ea9bd2d31 100644
--- a/apps/Kconfig
+++ b/apps/Kconfig
@@ -34,7 +34,3 @@ endmenu
menu "System NSH Add-Ons"
source "$APPSDIR/system/Kconfig"
endmenu
-
-menu "VSN board Add-Ons"
-source "$APPSDIR/vsn/Kconfig"
-endmenu
diff --git a/apps/Makefile b/apps/Makefile
index f087b7c33..19ad1c18b 100644
--- a/apps/Makefile
+++ b/apps/Makefile
@@ -46,10 +46,10 @@ APPDIR = ${shell pwd}
# appears in this directory as .config)
# SUBDIRS is the list of all directories containing Makefiles. It is used
# only for cleaning. namedapp must always be the first in the list. This
-# list can be extended by the .config file as well
+# list can be extended by the .config file as well.
CONFIGURED_APPS =
-#SUBDIRS = examples graphics interpreters modbus namedapp nshlib netutils system vsn
+#SUBDIRS = examples graphics interpreters modbus namedapp nshlib netutils system
ALL_SUBDIRS = $(dir $(shell /usr/bin/find . -name Makefile))
SUBDIRS = namedapp/ $(filter-out ./ ./namedapp/ ./examples/,$(ALL_SUBDIRS))
@@ -73,15 +73,16 @@ SUBDIRS = namedapp/ $(filter-out ./ ./namedapp/ ./examples/,$(ALL_SUBDIRS))
ifeq ($(CONFIG_NUTTX_NEWCONFIG),y)
+# namedapp/Make.defs must be included first
+
+-include namedapp/Make.defs
-include examples/Make.defs
-include graphics/Make.defs
-include interpreters/Make.defs
-include modbus/Make.defs
--include namedapp/Make.defs
-include netutils/Make.defs
-include nshlib/Make.defs
-include system/Make.defs
--include vsn/Make.defs
# INSTALLED_APPS is the list of currently available application directories. It
# is the same as CONFIGURED_APPS, but filtered to exclude any non-existent
diff --git a/apps/README.txt b/apps/README.txt
index f9c9ececd..7a379254e 100644
--- a/apps/README.txt
+++ b/apps/README.txt
@@ -107,7 +107,7 @@ NuttX is configured. .config is included in the toplevel apps/Makefile.
As a minimum, this configuration file must define files to add to the
CONFIGURED_APPS list like:
- CONFIGURED_APPS += examples/hello vsn/poweroff
+ CONFIGURED_APPS += examples/hello system/poweroff
Named Start-Up main() function
------------------------------
diff --git a/apps/drivers/device/cdev.cpp b/apps/drivers/device/cdev.cpp
index 6b8bf0c2d..d07d26e82 100644
--- a/apps/drivers/device/cdev.cpp
+++ b/apps/drivers/device/cdev.cpp
@@ -74,7 +74,7 @@ static int cdev_poll(struct file *filp, struct pollfd *fds, bool setup);
* Note that we use the GNU extension syntax here because we don't get designated
* initialisers in gcc 4.6.
*/
-static const struct file_operations cdev_fops = {
+const struct file_operations CDev::fops = {
open : cdev_open,
close : cdev_close,
read : cdev_read,
@@ -118,7 +118,7 @@ CDev::init()
goto out;
// now register the driver
- ret = register_driver(_devname, &cdev_fops, 0666, (void *)this);
+ ret = register_driver(_devname, &fops, 0666, (void *)this);
if (ret != OK)
goto out;
diff --git a/apps/drivers/device/device.h b/apps/drivers/device/device.h
index 98dbf8bfb..9af678465 100644
--- a/apps/drivers/device/device.h
+++ b/apps/drivers/device/device.h
@@ -287,6 +287,12 @@ public:
protected:
/**
+ * Pointer to the default cdev file operations table; useful for
+ * registering clone devices etc.
+ */
+ static const struct file_operations fops;
+
+ /**
* Check the current state of the device for poll events from the
* perspective of the file.
*
diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs
index a6e0ae88e..d03b976d2 100644
--- a/apps/examples/Make.defs
+++ b/apps/examples/Make.defs
@@ -58,7 +58,7 @@ ifeq ($(CONFIG_EXAMPLES_DHCPD),y)
CONFIGURED_APPS += examples/dhcpd
endif
-ifeq ($(CONFIG_EXAMPLE_DISCOVER),y)
+ifeq ($(CONFIG_EXAMPLES_DISCOVER),y)
CONFIGURED_APPS += examples/discover
endif
@@ -218,6 +218,10 @@ ifeq ($(CONFIG_EXAMPLES_USBTERM),y)
CONFIGURED_APPS += examples/usbterm
endif
+ifeq ($(CONFIG_EXAMPLES_WATCHDOG),y)
+CONFIGURED_APPS += examples/watchdog
+endif
+
ifeq ($(CONFIG_EXAMPLES_WGET),y)
CONFIGURED_APPS += examples/wget
endif
diff --git a/apps/examples/README.txt b/apps/examples/README.txt
index 12d6d3892..763427e32 100644
--- a/apps/examples/README.txt
+++ b/apps/examples/README.txt
@@ -60,20 +60,20 @@ examples/buttons
This is a simple configuration that may be used to test the board-
specific button interfaces. Configuration options:
- CONFIG_ARCH_BUTTONS - Must be defined for button support
- CONFIG_EXAMPLE_BUTTONS_MIN - Lowest button number (MIN=0)
- CONFIG_EXAMPLE_BUTTONS_MAX - Highest button number (MAX=7)
+ CONFIG_ARCH_BUTTONS - Must be defined for button support
+ CONFIG_EXAMPLES_BUTTONS_MIN - Lowest button number (MIN=0)
+ CONFIG_EXAMPLES_BUTTONS_MAX - Highest button number (MAX=7)
- CONFIG_ARCH_IRQBUTTONS - Must be defined for interrupting button support
- CONFIG_EXAMPLE_IRQBUTTONS_MIN - Lowest interrupting button number (MIN=0)
- CONFIG_EXAMPLE_IRQBUTTONS_MAX - Highest interrupting button number (MAX=7)
+ CONFIG_ARCH_IRQBUTTONS - Must be defined for interrupting button support
+ CONFIG_EXAMPLES_IRQBUTTONS_MIN - Lowest interrupting button number (MIN=0)
+ CONFIG_EXAMPLES_IRQBUTTONS_MAX - Highest interrupting button number (MAX=7)
Name strings for buttons:
- CONFIG_EXAMPLE_BUTTONS_NAME0, CONFIG_EXAMPLE_BUTTONS_NAME1,
- CONFIG_EXAMPLE_BUTTONS_NAME2, CONFIG_EXAMPLE_BUTTONS_NAME3,
- CONFIG_EXAMPLE_BUTTONS_NAME4, CONFIG_EXAMPLE_BUTTONS_NAME5,
- CONFIG_EXAMPLE_BUTTONS_NAME6, CONFIG_EXAMPLE_BUTTONS_NAME7,
+ CONFIG_EXAMPLES_BUTTONS_NAME0, CONFIG_EXAMPLES_BUTTONS_NAME1,
+ CONFIG_EXAMPLES_BUTTONS_NAME2, CONFIG_EXAMPLES_BUTTONS_NAME3,
+ CONFIG_EXAMPLES_BUTTONS_NAME4, CONFIG_EXAMPLES_BUTTONS_NAME5,
+ CONFIG_EXAMPLES_BUTTONS_NAME6, CONFIG_EXAMPLES_BUTTONS_NAME7,
Additional architecture-/board- specific configuration settings may also
be required.
@@ -260,10 +260,10 @@ examples/dhcpd
configuration settings)
CONFIG_NET_BROADCAST=y - UDP broadcast support is needed.
- CONFIG_EXAMPLE_DHCPD_NOMAC - (May be defined to use software assigned MAC)
- CONFIG_EXAMPLE_DHCPD_IPADDR - Target IP address
- CONFIG_EXAMPLE_DHCPD_DRIPADDR - Default router IP addess
- CONFIG_EXAMPLE_DHCPD_NETMASK - Network mask
+ CONFIG_EXAMPLES_DHCPD_NOMAC - (May be defined to use software assigned MAC)
+ CONFIG_EXAMPLES_DHCPD_IPADDR - Target IP address
+ CONFIG_EXAMPLES_DHCPD_DRIPADDR - Default router IP addess
+ CONFIG_EXAMPLES_DHCPD_NETMASK - Network mask
See also CONFIG_NETUTILS_DHCPD_* settings described elsewhere
and used in netutils/dhcpd/dhcpd.c. These settings are required
@@ -291,11 +291,11 @@ examples/discover
NuttX configuration settings:
- CONFIG_EXAMPLE_DISCOVER_DHCPC - DHCP Client
- CONFIG_EXAMPLE_DISCOVER_NOMAC - Use canned MAC address
- CONFIG_EXAMPLE_DISCOVER_IPADDR - Target IP address
- CONFIG_EXAMPLE_DISCOVER_DRIPADDR - Router IP address
- CONFIG_EXAMPLE_DISCOVER_NETMASK - Network Mask
+ CONFIG_EXAMPLES_DISCOVER_DHCPC - DHCP Client
+ CONFIG_EXAMPLES_DISCOVER_NOMAC - Use canned MAC address
+ CONFIG_EXAMPLES_DISCOVER_IPADDR - Target IP address
+ CONFIG_EXAMPLES_DISCOVER_DRIPADDR - Router IP address
+ CONFIG_EXAMPLES_DISCOVER_NETMASK - Network Mask
examples/ftpc
^^^^^^^^^^^^^
@@ -367,12 +367,12 @@ examples/ftpd
If CONFIG_EXAMPLES_FTPD_NONETINIT is not defined, then the following may
be specified to customized the network configuration:
- CONFIG_EXAMPLE_FTPD_NOMAC - If the hardware has no MAC address of its
+ CONFIG_EXAMPLES_FTPD_NOMAC - If the hardware has no MAC address of its
own, define this =y to provide a bogus address for testing.
- CONFIG_EXAMPLE_FTPD_IPADDR - The target IP address. Default 10.0.0.2
- CONFIG_EXAMPLE_FTPD_DRIPADDR - The default router address. Default
+ CONFIG_EXAMPLES_FTPD_IPADDR - The target IP address. Default 10.0.0.2
+ CONFIG_EXAMPLES_FTPD_DRIPADDR - The default router address. Default
10.0.0.1
- CONFIG_EXAMPLE_FTPD_NETMASK - The network mask. Default: 255.255.255.0
+ CONFIG_EXAMPLES_FTPD_NETMASK - The network mask. Default: 255.255.255.0
Other required configuration settings: Of course TCP networking support
is required. But here are a couple that are less obvious:
@@ -465,15 +465,15 @@ examples/igmp
does not do much of value -- Much more is needed in order to verify
the IGMP features!
- * CONFIG_EXAMPLE_IGMP_NOMAC
+ * CONFIG_EXAMPLES_IGMP_NOMAC
Set if the hardware has no MAC address; one will be assigned
- * CONFIG_EXAMPLE_IGMP_IPADDR
+ * CONFIG_EXAMPLES_IGMP_IPADDR
Target board IP address
- * CONFIG_EXAMPLE_IGMP_DRIPADDR
+ * CONFIG_EXAMPLES_IGMP_DRIPADDR
Default router address
- * CONFIG_EXAMPLE_IGMP_NETMASK
+ * CONFIG_EXAMPLES_IGMP_NETMASK
Network mask
- * CONFIG_EXAMPLE_IGMP_GRPADDR
+ * CONFIG_EXAMPLES_IGMP_GRPADDR
Multicast group address
Applications using this example will need to provide an appconfig
@@ -1023,10 +1023,10 @@ examples/poll
CONFIG_NSOCKET_DESCRIPTORS - Defined to be greater than 0
CONFIG_NET_NTCP_READAHEAD_BUFFERS - Defined to be greater than zero
- CONFIG_EXAMPLE_POLL_NOMAC - (May be defined to use software assigned MAC)
- CONFIG_EXAMPLE_POLL_IPADDR - Target IP address
- CONFIG_EXAMPLE_POLL_DRIPADDR - Default router IP addess
- CONFIG_EXAMPLE_POLL_NETMASK - Network mask
+ CONFIG_EXAMPLES_POLL_NOMAC - (May be defined to use software assigned MAC)
+ CONFIG_EXAMPLES_POLL_IPADDR - Target IP address
+ CONFIG_EXAMPLES_POLL_DRIPADDR - Default router IP addess
+ CONFIG_EXAMPLES_POLL_NETMASK - Network mask
In order to for select to work with incoming connections, you
must also select:
@@ -1163,14 +1163,14 @@ examples/sendmail
Settings unique to this example include:
- CONFIG_EXAMPLE_SENDMAIL_NOMAC - May be defined to use software assigned MAC (optional)
- CONFIG_EXAMPLE_SENDMAIL_IPADDR - Target IP address (required)
- CONFIG_EXAMPLE_SENDMAIL_DRIPADDR - Default router IP addess (required)
- CONFIG_EXAMPLE_SENDMAILT_NETMASK - Network mask (required)
- CONFIG_EXAMPLE_SENDMAIL_RECIPIENT - The recipient of the email (required)
- CONFIG_EXAMPLE_SENDMAIL_SENDER - Optional. Default: "nuttx-testing@example.com"
- CONFIG_EXAMPLE_SENDMAIL_SUBJECT - Optional. Default: "Testing SMTP from NuttX"
- CONFIG_EXAMPLE_SENDMAIL_BODY - Optional. Default: "Test message sent by NuttX"
+ CONFIG_EXAMPLES_SENDMAIL_NOMAC - May be defined to use software assigned MAC (optional)
+ CONFIG_EXAMPLES_SENDMAIL_IPADDR - Target IP address (required)
+ CONFIG_EXAMPLES_SENDMAIL_DRIPADDR - Default router IP addess (required)
+ CONFIG_EXAMPLES_SENDMAILT_NETMASK - Network mask (required)
+ CONFIG_EXAMPLES_SENDMAIL_RECIPIENT - The recipient of the email (required)
+ CONFIG_EXAMPLES_SENDMAIL_SENDER - Optional. Default: "nuttx-testing@example.com"
+ CONFIG_EXAMPLES_SENDMAIL_SUBJECT - Optional. Default: "Testing SMTP from NuttX"
+ CONFIG_EXAMPLES_SENDMAIL_BODY - Optional. Default: "Test message sent by NuttX"
NOTE: This test has not been verified on the NuttX target environment.
As of this writing, unit-tested in the Cygwin/Linux host environment.
@@ -1213,12 +1213,12 @@ examples/telnetd
Default: SCHED_PRIORITY_DEFAULT
CONFIG_EXAMPLES_TELNETD_CLIENTSTACKSIZE - Stack size allocated for the
Telnet client. Default: 2048
- CONFIG_EXAMPLE_TELNETD_NOMAC - If the hardware has no MAC address of its
+ CONFIG_EXAMPLES_TELNETD_NOMAC - If the hardware has no MAC address of its
own, define this =y to provide a bogus address for testing.
- CONFIG_EXAMPLE_TELNETD_IPADDR - The target IP address. Default 10.0.0.2
- CONFIG_EXAMPLE_TELNETD_DRIPADDR - The default router address. Default
+ CONFIG_EXAMPLES_TELNETD_IPADDR - The target IP address. Default 10.0.0.2
+ CONFIG_EXAMPLES_TELNETD_DRIPADDR - The default router address. Default
10.0.0.1
- CONFIG_EXAMPLE_TELNETD_NETMASK - The network mask. Default: 255.255.255.0
+ CONFIG_EXAMPLES_TELNETD_NETMASK - The network mask. Default: 255.255.255.0
The appconfig file (apps/.config) should include:
@@ -1240,9 +1240,9 @@ examples/thttpd
CGI programs. see configs/README.txt for most THTTPD settings.
In addition to those, this example accepts:
- CONFIG_EXAMPLE_THTTPD_NOMAC - (May be defined to use software assigned MAC)
- CONFIG_EXAMPLE_THTTPD_DRIPADDR - Default router IP addess
- CONFIG_EXAMPLE_THTTPD_NETMASK - Network mask
+ CONFIG_EXAMPLES_THTTPD_NOMAC - (May be defined to use software assigned MAC)
+ CONFIG_EXAMPLES_THTTPD_DRIPADDR - Default router IP addess
+ CONFIG_EXAMPLES_THTTPD_NETMASK - Network mask
Applications using this example will need to provide an appconfig
file in the configuration directory with instruction to build applications
@@ -1335,11 +1335,11 @@ examples/uip
This is a port of uIP tiny webserver example application. Settings
specific to this example include:
- CONFIG_EXAMPLE_UIP_NOMAC - (May be defined to use software assigned MAC)
- CONFIG_EXAMPLE_UIP_IPADDR - Target IP address
- CONFIG_EXAMPLE_UIP_DRIPADDR - Default router IP addess
- CONFIG_EXAMPLE_UIP_NETMASK - Network mask
- CONFIG_EXAMPLE_UIP_DHCPC - Select to get IP address via DHCP
+ CONFIG_EXAMPLES_UIP_NOMAC - (May be defined to use software assigned MAC)
+ CONFIG_EXAMPLES_UIP_IPADDR - Target IP address
+ CONFIG_EXAMPLES_UIP_DRIPADDR - Default router IP addess
+ CONFIG_EXAMPLES_UIP_NETMASK - Network mask
+ CONFIG_EXAMPLES_UIP_DHCPC - Select to get IP address via DHCP
If you use DHCPC, then some special configuration network options are
required. These include:
@@ -1637,11 +1637,11 @@ examples/wget
A simple web client example. It will obtain a file from a server using the HTTP
protocol. Settings unique to this example include:
- CONFIG_EXAMPLE_WGET_URL - The URL of the file to get
- CONFIG_EXAMPLE_WGET_NOMAC - (May be defined to use software assigned MAC)
- CONFIG_EXAMPLE_WGET_IPADDR - Target IP address
- CONFIG_EXAMPLE_WGET_DRIPADDR - Default router IP addess
- CONFIG_EXAMPLE_WGET_NETMASK - Network mask
+ CONFIG_EXAMPLES_WGET_URL - The URL of the file to get
+ CONFIG_EXAMPLES_WGET_NOMAC - (May be defined to use software assigned MAC)
+ CONFIG_EXAMPLES_WGET_IPADDR - Target IP address
+ CONFIG_EXAMPLES_WGET_DRIPADDR - Default router IP addess
+ CONFIG_EXAMPLES_WGET_NETMASK - Network mask
This example uses netutils/webclient. Additional configuration settings apply
to that code as follows (but built-in defaults are probably OK):
diff --git a/apps/examples/adc/Kconfig b/apps/examples/adc/Kconfig
index b6dca047c..85c875deb 100644
--- a/apps/examples/adc/Kconfig
+++ b/apps/examples/adc/Kconfig
@@ -6,8 +6,32 @@
config EXAMPLES_ADC
bool "ADC example"
default n
+ depends on ADC
---help---
Enable the ADC example
if EXAMPLES_ADC
+
+config EXAMPLES_ADC_DEVPATH
+ string "ADC device path"
+ default "/dev/adc0"
+ ---help---
+ The default path to the ADC device. Default: /dev/adc0
+
+config EXAMPLES_ADC_NSAMPLES
+ int "Number of Sample Groups"
+ default 0
+ depends on !NSH_BUILTIN_APPS
+ ---help---
+ If NSH_BUILTIN_APPS is defined, then the number of samples is provided
+ on the command line and this value is ignored. Otherwise, this number
+ of samples is collected and the program terminates. Default: 0 (samples
+ are collected indefinitely).
+
+config EXAMPLES_ADC_GROUPSIZE
+ int "Number of Samples per Group"
+ default 4
+ ---help---
+ The number of samples to read at once. Default: 4
+
endif
diff --git a/apps/examples/adc/adc_main.c b/apps/examples/adc/adc_main.c
index 4797265db..404fba8c1 100644
--- a/apps/examples/adc/adc_main.c
+++ b/apps/examples/adc/adc_main.c
@@ -57,6 +57,14 @@
* Pre-processor Definitions
****************************************************************************/
+/* Use CONFIG_EXAMPLES_ADC_NSAMPLES == 0 to mean to collect samples
+ * indefinitely.
+ */
+
+#ifndef CONFIG_EXAMPLES_ADC_NSAMPLES
+# define CONFIG_EXAMPLES_ADC_NSAMPLES 0
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -249,7 +257,7 @@ int adc_main(int argc, char *argv[])
adc_devpath(&g_adcstate, CONFIG_EXAMPLES_ADC_DEVPATH);
-#ifdef CONFIG_EXAMPLES_ADC_NSAMPLES
+#if CONFIG_EXAMPLES_ADC_NSAMPLES > 0
g_adcstate.count = CONFIG_EXAMPLES_ADC_NSAMPLES;
#else
g_adcstate.count = 1;
@@ -267,7 +275,7 @@ int adc_main(int argc, char *argv[])
* samples that we collect before returning. Otherwise, we never return
*/
-#if defined(CONFIG_NSH_BUILTIN_APPS) || defined(CONFIG_EXAMPLES_ADC_NSAMPLES)
+#if defined(CONFIG_NSH_BUILTIN_APPS) || CONFIG_EXAMPLES_ADC_NSAMPLES > 0
message("adc_main: g_adcstate.count: %d\n", g_adcstate.count);
#endif
@@ -290,7 +298,7 @@ int adc_main(int argc, char *argv[])
#if defined(CONFIG_NSH_BUILTIN_APPS)
for (; g_adcstate.count > 0; g_adcstate.count--)
-#elif defined(CONFIG_EXAMPLES_ADC_NSAMPLES)
+#elif CONFIG_EXAMPLES_ADC_NSAMPLES > 0
for (g_adcstate.count = 0; g_adcstate.count < CONFIG_EXAMPLES_ADC_NSAMPLES; g_adcstate.count++)
#else
for (;;)
diff --git a/apps/examples/buttons/Kconfig b/apps/examples/buttons/Kconfig
index 9c34b37bc..d145867fc 100644
--- a/apps/examples/buttons/Kconfig
+++ b/apps/examples/buttons/Kconfig
@@ -7,7 +7,57 @@ config EXAMPLES_BUTTONS
bool "Buttons example"
default n
---help---
- Enable the buttons example
+ Enable the buttons example. May require ARCH_BUTTONS on some boards.
if EXAMPLES_BUTTONS
+config EXAMPLES_BUTTONS_MIN
+int "Lowest Button Number"
+default 0
+
+config EXAMPLES_BUTTONS_MAX
+int "Highest Button Number"
+default 7
+
+if ARCH_IRQBUTTONS
+config EXAMPLES_IRQBUTTONS_MIN
+int "Lowest Interrupting Button Number"
+default 0
+
+config EXAMPLES_IRQBUTTONS_MAX
+int "Highest Interrupting Button Number"
+default 7
+
+config EXAMPLES_BUTTONS_NAME0
+string "Button 0 Name"
+default "Button 0"
+
+config EXAMPLES_BUTTONS_NAME1
+string "Button 1 Name"
+default "Button 1"
+
+config EXAMPLES_BUTTONS_NAME2
+string "Button 2 Name"
+default "Button 2"
+
+config EXAMPLES_BUTTONS_NAME3
+string "Button 3 Name"
+default "Button 3"
+
+config EXAMPLES_BUTTONS_NAME4
+string "Button 4 Name"
+default "Button 4"
+
+config EXAMPLES_BUTTONS_NAME5
+string "Button 5 Name"
+default "Button 5"
+
+config EXAMPLES_BUTTONS_NAME6
+string "Button 6 Name"
+default "Button 6"
+
+config EXAMPLES_BUTTONS_NAME7
+string "Button 7 Name"
+default "Button 7"
+
+endif
endif
diff --git a/apps/examples/buttons/buttons_main.c b/apps/examples/buttons/buttons_main.c
index a3f6449d4..5f25c1ef1 100644
--- a/apps/examples/buttons/buttons_main.c
+++ b/apps/examples/buttons/buttons_main.c
@@ -61,60 +61,60 @@
# error "CONFIG_ARCH_BUTTONS is not defined in the configuration"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME0
-# define CONFIG_EXAMPLE_BUTTONS_NAME0 "BUTTON0"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME0
+# define CONFIG_EXAMPLES_BUTTONS_NAME0 "BUTTON0"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME1
-# define CONFIG_EXAMPLE_BUTTONS_NAME1 "BUTTON1"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME1
+# define CONFIG_EXAMPLES_BUTTONS_NAME1 "BUTTON1"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME2
-# define CONFIG_EXAMPLE_BUTTONS_NAME2 "BUTTON2"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME2
+# define CONFIG_EXAMPLES_BUTTONS_NAME2 "BUTTON2"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME3
-# define CONFIG_EXAMPLE_BUTTONS_NAME3 "BUTTON3"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME3
+# define CONFIG_EXAMPLES_BUTTONS_NAME3 "BUTTON3"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME4
-# define CONFIG_EXAMPLE_BUTTONS_NAME4 "BUTTON4"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME4
+# define CONFIG_EXAMPLES_BUTTONS_NAME4 "BUTTON4"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME5
-# define CONFIG_EXAMPLE_BUTTONS_NAME5 "BUTTON5"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME5
+# define CONFIG_EXAMPLES_BUTTONS_NAME5 "BUTTON5"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME6
-# define CONFIG_EXAMPLE_BUTTONS_NAME6 "BUTTON6"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME6
+# define CONFIG_EXAMPLES_BUTTONS_NAME6 "BUTTON6"
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_NAME7
-# define CONFIG_EXAMPLE_BUTTONS_NAME7 "BUTTON7"
+#ifndef CONFIG_EXAMPLES_BUTTONS_NAME7
+# define CONFIG_EXAMPLES_BUTTONS_NAME7 "BUTTON7"
#endif
#define BUTTON_MIN 0
#define BUTTON_MAX 7
-#ifndef CONFIG_EXAMPLE_BUTTONS_MIN
-# define CONFIG_EXAMPLE_BUTTONS_MIN BUTTON_MIN
+#ifndef CONFIG_EXAMPLES_BUTTONS_MIN
+# define CONFIG_EXAMPLES_BUTTONS_MIN BUTTON_MIN
#endif
-#ifndef CONFIG_EXAMPLE_BUTTONS_MAX
-# define CONFIG_EXAMPLE_BUTTONS_MAX BUTTON_MAX
+#ifndef CONFIG_EXAMPLES_BUTTONS_MAX
+# define CONFIG_EXAMPLES_BUTTONS_MAX BUTTON_MAX
#endif
-#if CONFIG_EXAMPLE_BUTTONS_MIN > CONFIG_EXAMPLE_BUTTONS_MAX
-# error "CONFIG_EXAMPLE_BUTTONS_MIN > CONFIG_EXAMPLE_BUTTONS_MAX"
+#if CONFIG_EXAMPLES_BUTTONS_MIN > CONFIG_EXAMPLES_BUTTONS_MAX
+# error "CONFIG_EXAMPLES_BUTTONS_MIN > CONFIG_EXAMPLES_BUTTONS_MAX"
#endif
-#if CONFIG_EXAMPLE_BUTTONS_MAX > 7
-# error "CONFIG_EXAMPLE_BUTTONS_MAX > 7"
+#if CONFIG_EXAMPLES_BUTTONS_MAX > 7
+# error "CONFIG_EXAMPLES_BUTTONS_MAX > 7"
#endif
-#ifndef CONFIG_EXAMPLE_IRQBUTTONS_MIN
-# define CONFIG_EXAMPLE_IRQBUTTONS_MIN CONFIG_EXAMPLE_BUTTONS_MIN
+#ifndef CONFIG_EXAMPLES_IRQBUTTONS_MIN
+# define CONFIG_EXAMPLES_IRQBUTTONS_MIN CONFIG_EXAMPLES_BUTTONS_MIN
#endif
-#ifndef CONFIG_EXAMPLE_IRQBUTTONS_MAX
-# define CONFIG_EXAMPLE_IRQBUTTONS_MAX CONFIG_EXAMPLE_BUTTONS_MAX
+#ifndef CONFIG_EXAMPLES_IRQBUTTONS_MAX
+# define CONFIG_EXAMPLES_IRQBUTTONS_MAX CONFIG_EXAMPLES_BUTTONS_MAX
#endif
-#if CONFIG_EXAMPLE_IRQBUTTONS_MIN > CONFIG_EXAMPLE_IRQBUTTONS_MAX
-# error "CONFIG_EXAMPLE_IRQBUTTONS_MIN > CONFIG_EXAMPLE_IRQBUTTONS_MAX"
+#if CONFIG_EXAMPLES_IRQBUTTONS_MIN > CONFIG_EXAMPLES_IRQBUTTONS_MAX
+# error "CONFIG_EXAMPLES_IRQBUTTONS_MIN > CONFIG_EXAMPLES_IRQBUTTONS_MAX"
#endif
-#if CONFIG_EXAMPLE_IRQBUTTONS_MAX > 7
-# error "CONFIG_EXAMPLE_IRQBUTTONS_MAX > 7"
+#if CONFIG_EXAMPLES_IRQBUTTONS_MAX > 7
+# error "CONFIG_EXAMPLES_IRQBUTTONS_MAX > 7"
#endif
#ifndef MIN
@@ -124,8 +124,8 @@
# define MAX(a,b) (a > b ? a : b)
#endif
-#define MIN_BUTTON MIN(CONFIG_EXAMPLE_BUTTONS_MIN, CONFIG_EXAMPLE_IRQBUTTONS_MIN)
-#define MAX_BUTTON MAX(CONFIG_EXAMPLE_BUTTONS_MAX, CONFIG_EXAMPLE_IRQBUTTONS_MAX)
+#define MIN_BUTTON MIN(CONFIG_EXAMPLES_BUTTONS_MIN, CONFIG_EXAMPLES_IRQBUTTONS_MIN)
+#define MAX_BUTTON MAX(CONFIG_EXAMPLES_BUTTONS_MAX, CONFIG_EXAMPLES_IRQBUTTONS_MAX)
#define NUM_BUTTONS (MAX_BUTTON - MIN_BUTTON + 1)
#define BUTTON_INDEX(b) ((b)-MIN_BUTTON)
@@ -187,7 +187,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
{
#if MIN_BUTTON < 1
{
- CONFIG_EXAMPLE_BUTTONS_NAME0,
+ CONFIG_EXAMPLES_BUTTONS_NAME0,
#ifdef CONFIG_ARCH_IRQBUTTONS
button0_handler
#endif
@@ -195,7 +195,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MIN_BUTTON < 2 && MAX_BUTTON > 0
{
- CONFIG_EXAMPLE_BUTTONS_NAME1,
+ CONFIG_EXAMPLES_BUTTONS_NAME1,
#ifdef CONFIG_ARCH_IRQBUTTONS
button1_handler
#endif
@@ -203,7 +203,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MIN_BUTTON < 3 && MAX_BUTTON > 1
{
- CONFIG_EXAMPLE_BUTTONS_NAME2,
+ CONFIG_EXAMPLES_BUTTONS_NAME2,
#ifdef CONFIG_ARCH_IRQBUTTONS
button2_handler
#endif
@@ -211,7 +211,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MIN_BUTTON < 4 && MAX_BUTTON > 2
{
- CONFIG_EXAMPLE_BUTTONS_NAME3,
+ CONFIG_EXAMPLES_BUTTONS_NAME3,
#ifdef CONFIG_ARCH_IRQBUTTONS
button3_handler
#endif
@@ -219,7 +219,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MIN_BUTTON < 5 && MAX_BUTTON > 3
{
- CONFIG_EXAMPLE_BUTTONS_NAME4,
+ CONFIG_EXAMPLES_BUTTONS_NAME4,
#ifdef CONFIG_ARCH_IRQBUTTONS
button4_handler
#endif
@@ -227,7 +227,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MIN_BUTTON < 6 && MAX_BUTTON > 4
{
- CONFIG_EXAMPLE_BUTTONS_NAME5,
+ CONFIG_EXAMPLES_BUTTONS_NAME5,
#ifdef CONFIG_ARCH_IRQBUTTONS
button5_handler
#endif
@@ -235,7 +235,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MIN_BUTTON < 7 && MAX_BUTTON > 5
{
- CONFIG_EXAMPLE_BUTTONS_NAME6,
+ CONFIG_EXAMPLES_BUTTONS_NAME6,
#ifdef CONFIG_ARCH_IRQBUTTONS
button6_handler
#endif
@@ -243,7 +243,7 @@ static const struct button_info_s g_buttoninfo[NUM_BUTTONS] =
#endif
#if MAX_BUTTON > 6
{
- CONFIG_EXAMPLE_BUTTONS_NAME7,
+ CONFIG_EXAMPLES_BUTTONS_NAME7,
#ifdef CONFIG_ARCH_IRQBUTTONS
button7_handler
#endif
@@ -419,7 +419,7 @@ int buttons_main(int argc, char *argv[])
/* Register to recieve button interrupts */
#ifdef CONFIG_ARCH_IRQBUTTONS
- for (i = CONFIG_EXAMPLE_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLE_IRQBUTTONS_MAX; i++)
+ for (i = CONFIG_EXAMPLES_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLES_IRQBUTTONS_MAX; i++)
{
xcpt_t oldhandler = up_irqbutton(i, g_buttoninfo[BUTTON_INDEX(i)].handler);
@@ -488,7 +488,7 @@ int buttons_main(int argc, char *argv[])
/* Un-register button handlers */
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_NSH_BUILTIN_APPS)
- for (i = CONFIG_EXAMPLE_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLE_IRQBUTTONS_MAX; i++)
+ for (i = CONFIG_EXAMPLES_IRQBUTTONS_MIN; i <= CONFIG_EXAMPLES_IRQBUTTONS_MAX; i++)
{
(void)up_irqbutton(i, NULL);
}
diff --git a/apps/examples/poll/net_listener.c b/apps/examples/poll/net_listener.c
index 81ad7cdcc..2be98673c 100644
--- a/apps/examples/poll/net_listener.c
+++ b/apps/examples/poll/net_listener.c
@@ -290,14 +290,14 @@ static inline bool net_mksocket(struct net_listener_s *nls)
static void net_configure(void)
{
struct in_addr addr;
-#if defined(CONFIG_EXAMPLE_POLL_NOMAC)
+#if defined(CONFIG_EXAMPLES_POLL_NOMAC)
uint8_t mac[IFHWADDRLEN];
#endif
/* Configure uIP */
/* Many embedded network interfaces must have a software assigned MAC */
-#ifdef CONFIG_EXAMPLE_POLL_NOMAC
+#ifdef CONFIG_EXAMPLES_POLL_NOMAC
mac[0] = 0x00;
mac[1] = 0xe0;
mac[2] = 0xde;
@@ -309,17 +309,17 @@ static void net_configure(void)
/* Set up our host address */
- addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_IPADDR);
+ addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_IPADDR);
uip_sethostaddr("eth0", &addr);
/* Set up the default router address */
- addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_DRIPADDR);
+ addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_DRIPADDR);
uip_setdraddr("eth0", &addr);
/* Setup the subnet mask */
- addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_NETMASK);
+ addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_NETMASK);
uip_setnetmask("eth0", &addr);
}
diff --git a/apps/examples/poll/net_reader.c b/apps/examples/poll/net_reader.c
index 8a13618c3..2f23bab3c 100644
--- a/apps/examples/poll/net_reader.c
+++ b/apps/examples/poll/net_reader.c
@@ -83,14 +83,14 @@
static void net_configure(void)
{
struct in_addr addr;
-#if defined(CONFIG_EXAMPLE_POLL_NOMAC)
+#if defined(CONFIG_EXAMPLES_POLL_NOMAC)
uint8_t mac[IFHWADDRLEN];
#endif
/* Configure uIP */
/* Many embedded network interfaces must have a software assigned MAC */
-#ifdef CONFIG_EXAMPLE_POLL_NOMAC
+#ifdef CONFIG_EXAMPLES_POLL_NOMAC
mac[0] = 0x00;
mac[1] = 0xe0;
mac[2] = 0xde;
@@ -102,17 +102,17 @@ static void net_configure(void)
/* Set up our host address */
- addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_IPADDR);
+ addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_IPADDR);
uip_sethostaddr("eth0", &addr);
/* Set up the default router address */
- addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_DRIPADDR);
+ addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_DRIPADDR);
uip_setdraddr("eth0", &addr);
/* Setup the subnet mask */
- addr.s_addr = HTONL(CONFIG_EXAMPLE_POLL_NETMASK);
+ addr.s_addr = HTONL(CONFIG_EXAMPLES_POLL_NETMASK);
uip_setnetmask("eth0", &addr);
}
diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig
index c0f7d6a92..d12a32973 100644
--- a/apps/nshlib/Kconfig
+++ b/apps/nshlib/Kconfig
@@ -291,19 +291,18 @@ config NSH_CONSOLE
console front-end is selected (/dev/console).
Normally, the serial console device is a UART and RS-232
- interface. However, if CONFIG_USBDEV is defined, then a USB
+ interface. However, if USBDEV is defined, then a USB
serial device may, instead, be used if the one of
the following are defined:
- CONFIG_PL2303 and CONFIG_PL2303_CONSOLE - Sets up the
- Prolifics PL2303 emulation as a console device at /dev/console.
+ PL2303 and PL2303_CONSOLE - Set up the Prolifics PL2303
+ emulation as a console device at /dev/console.
- CONFIG_CDCACM and CONFIG_CDCACM_CONSOLE - Sets up the
- CDC/ACM serial device as a console device at dev/console.
+ CDCACM and CDCACM_CONSOLE - Set up the CDC/ACM serial
+ device as a console device at dev/console.
- CONFIG_NSH_USBCONSOLE and CONFIG_NSH_USBCONDEV - Sets up the
- some other USB serial device as the NSH console (not necessarily
- dev/console).
+ NSH_USBCONSOLE and NSH_USBCONDEV - Sets up some other USB
+ serial device as the NSH console (not necessarily dev/console).
config NSH_USBCONSOLE
bool "Use a USB console"
@@ -311,20 +310,20 @@ config NSH_USBCONSOLE
depends on NSH_CONSOLE && USBDEV
---help---
If defined, then the an arbitrary USB device may be used
- to as the NSH console. In this case, CONFIG_NSH_USBCONDEV
- must be defined to indicate which USB device to use as
- the console.
+ to as the NSH console. In this case, NSH_USBCONDEV must
+ be defined to indicate which USB device to use as the
+ console.
config NSH_USBCONDEV
string "USB console device"
default "/dev/ttyACM0"
depends on NSH_USBCONSOLE
---help---
- If CONFIG_NSH_USBCONSOLE is set to 'y', then CONFIG_NSH_USBCONDEV
- must also be set to select the USB device used to support
- the NSH console. This should be set to the quoted name of a
+ If NSH_USBCONSOLE is set to 'y', then NSH_USBCONDEV must
+ also be set to select the USB device used to support the
+ NSH console. This should be set to the quoted name of a
readable/write-able USB driver such as:
- CONFIG_NSH_USBCONDEV="/dev/ttyACM0".
+ NSH_USBCONDEV="/dev/ttyACM0".
config UBSDEV_MINOR
int "USB console device minor number"
@@ -448,6 +447,35 @@ config NSH_IOBUFFER_SIZE
---help---
Determines the size of the I/O buffer to use for sending/
receiving TELNET commands/reponses. Default: 512
+
+config NSH_TELNET_LOGIN
+ bool "Telnet Login"
+ default n
+ ---help---
+ If defined, then the Telnet user will be required to provide a
+ username and password to start the NSH shell.
+
+if NSH_TELNET_LOGIN
+
+config NSH_TELNET_USERNAME
+ string "Login Username"
+ default "admin"
+ ---help---
+ Login user name. Default: "admin"
+
+config NSH_TELNET_PASSWORD
+ string "Login Password"
+ default "nuttx"
+ ---help---
+ Login password: Default: "nuttx"
+
+config NSH_TELNET_FAILCOUNT
+ int "Login Retry Count"
+ default 3
+ ---help---
+ Number of login retry attempts.
+
+endif
endif
config NSH_DHCPC
diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h
index e6dd2683b..7188477ce 100644
--- a/apps/nshlib/nsh.h
+++ b/apps/nshlib/nsh.h
@@ -164,10 +164,19 @@
* Default: SCHED_PRIORITY_DEFAULT
* CONFIG_NSH_TELNETD_DAEMONSTACKSIZE - Stack size allocated for the
* Telnet daemon. Default: 2048
- * CONFIG_NSH_TELNETD_CLIENTPRIO- Priority of the Telnet client.
+ * CONFIG_NSH_TELNETD_CLIENTPRIO - Priority of the Telnet client.
* Default: SCHED_PRIORITY_DEFAULT
* CONFIG_NSH_TELNETD_CLIENTSTACKSIZE - Stack size allocated for the
* Telnet client. Default: 2048
+ * CONFIG_NSH_TELNET_LOGIN - Support a simple Telnet login.
+ *
+ * If CONFIG_NSH_TELNET_LOGIN is defined, then these additional
+ * options may be specified:
+ *
+ * CONFIG_NSH_TELNET_USERNAME - Login user name. Default: "admin"
+ * CONFIG_NSH_TELNET_PASSWORD - Login password: Default: "nuttx"
+ * CONFIG_NSH_TELNET_FAILCOUNT - Number of login retry attempts.
+ * Default 3.
*/
#ifndef CONFIG_NSH_TELNETD_PORT
@@ -190,6 +199,22 @@
# define CONFIG_NSH_TELNETD_CLIENTSTACKSIZE 2048
#endif
+#ifdef CONFIG_NSH_TELNET_LOGIN
+
+# ifndef CONFIG_NSH_TELNET_USERNAME
+# define CONFIG_NSH_TELNET_USERNAME "admin"
+# endif
+
+# ifndef CONFIG_NSH_TELNET_PASSWORD
+# define CONFIG_NSH_TELNET_PASSWORD "nuttx"
+# endif
+
+# ifndef CONFIG_NSH_TELNET_FAILCOUNT
+# define CONFIG_NSH_TELNET_FAILCOUNT 3
+# endif
+
+#endif /* CONFIG_NSH_TELNET_LOGIN */
+
/* Verify support for ROMFS /etc directory support options */
#ifdef CONFIG_NSH_ROMFSETC
@@ -364,6 +389,14 @@ typedef int (*cmd_t)(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
****************************************************************************/
extern const char g_nshgreeting[];
+#if defined(CONFIG_NSH_TELNET_LOGIN) && defined(CONFIG_NSH_TELNET)
+extern const char g_telnetgreeting[];
+extern const char g_userprompt[];
+extern const char g_passwordprompt[];
+extern const char g_loginsuccess[];
+extern const char g_badcredentials[];
+extern const char g_loginfailure[];
+#endif
extern const char g_nshprompt[];
extern const char g_nshsyntax[];
extern const char g_fmtargrequired[];
diff --git a/apps/nshlib/nsh_console.c b/apps/nshlib/nsh_console.c
index b066e71f5..1b8f5f6ac 100644
--- a/apps/nshlib/nsh_console.c
+++ b/apps/nshlib/nsh_console.c
@@ -75,12 +75,17 @@ struct serialsave_s
static FAR struct nsh_vtbl_s *nsh_consoleclone(FAR struct nsh_vtbl_s *vtbl);
#endif
static void nsh_consolerelease(FAR struct nsh_vtbl_s *vtbl);
-static ssize_t nsh_consolewrite(FAR struct nsh_vtbl_s *vtbl, FAR const void *buffer, size_t nbytes);
-static int nsh_consoleoutput(FAR struct nsh_vtbl_s *vtbl, const char *fmt, ...);
+static ssize_t nsh_consolewrite(FAR struct nsh_vtbl_s *vtbl,
+ FAR const void *buffer, size_t nbytes);
+static int nsh_consoleoutput(FAR struct nsh_vtbl_s *vtbl,
+ FAR const char *fmt, ...);
static FAR char *nsh_consolelinebuffer(FAR struct nsh_vtbl_s *vtbl);
-static void nsh_consoleredirect(FAR struct nsh_vtbl_s *vtbl, int fd, FAR uint8_t *save);
-static void nsh_consoleundirect(FAR struct nsh_vtbl_s *vtbl, FAR uint8_t *save);
-static void nsh_consoleexit(FAR struct nsh_vtbl_s *vtbl, int exitstatus);
+static void nsh_consoleredirect(FAR struct nsh_vtbl_s *vtbl, int fd,
+ FAR uint8_t *save);
+static void nsh_consoleundirect(FAR struct nsh_vtbl_s *vtbl,
+ FAR uint8_t *save);
+static void nsh_consoleexit(FAR struct nsh_vtbl_s *vtbl, int exitstatus)
+ noreturn_function;
/****************************************************************************
* Private Data
diff --git a/apps/nshlib/nsh_console.h b/apps/nshlib/nsh_console.h
index 53e8c7897..4dc2938cb 100644
--- a/apps/nshlib/nsh_console.h
+++ b/apps/nshlib/nsh_console.h
@@ -109,7 +109,7 @@ struct nsh_vtbl_s
FAR char *(*linebuffer)(FAR struct nsh_vtbl_s *vtbl);
void (*redirect)(FAR struct nsh_vtbl_s *vtbl, int fd, FAR uint8_t *save);
void (*undirect)(FAR struct nsh_vtbl_s *vtbl, FAR uint8_t *save);
- void (*exit)(FAR struct nsh_vtbl_s *vtbl, int exitstatus);
+ void (*exit)(FAR struct nsh_vtbl_s *vtbl, int exitstatus) noreturn_function;
/* Parser state data */
diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c
index ba597a062..df2f7c3e3 100644
--- a/apps/nshlib/nsh_parse.c
+++ b/apps/nshlib/nsh_parse.c
@@ -395,6 +395,17 @@ const char g_nshgreeting[] = "\nNuttShell (NSH) NuttX-" CONFIG_VERSION_STR
const char g_nshgreeting[] = "\nNuttShell (NSH)\n";
#endif
+/* Telnet login prompts */
+
+#if defined(CONFIG_NSH_TELNET_LOGIN) && defined(CONFIG_NSH_TELNET)
+const char g_telnetgreeting[] = "\nWelcome to NuttShell(NSH) Telnet Server...\n";
+const char g_userprompt[] = "login: ";
+const char g_passwordprompt[] = "password: ";
+const char g_loginsuccess[] = "\nUser Logged-in!\n";
+const char g_badcredentials[] = "\nInvalid username or password\n";
+const char g_loginfailure[] = "Login failed!\n";
+#endif
+
/* The NSH prompt */
const char g_nshprompt[] = "nsh> ";
diff --git a/apps/nshlib/nsh_telnetd.c b/apps/nshlib/nsh_telnetd.c
index 0117aad04..478935d7f 100644
--- a/apps/nshlib/nsh_telnetd.c
+++ b/apps/nshlib/nsh_telnetd.c
@@ -43,6 +43,7 @@
#include <unistd.h>
#include <assert.h>
#include <debug.h>
+#include <string.h>
#include <apps/netutils/telnetd.h>
@@ -55,6 +56,18 @@
* Pre-processor Definitions
****************************************************************************/
+#ifdef CONFIG_NSH_TELNET_LOGIN
+
+# define TELNET_IAC 255
+# define TELNET_WILL 251
+# define TELNET_WONT 252
+# define TELNET_DO 253
+# define TELNET_DONT 254
+# define TELNET_USE_ECHO 1
+# define TELNET_NOTUSE_ECHO 0
+
+#endif /* CONFIG_NSH_TELNET_LOGIN */
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -76,6 +89,91 @@
****************************************************************************/
/****************************************************************************
+ * Name: nsh_telnetecho
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_TELNET_LOGIN
+void nsh_telnetecho(struct console_stdio_s *pstate, uint8_t is_use)
+{
+ uint8_t optbuf[4];
+ optbuf[0] = TELNET_IAC;
+ optbuf[1] = (is_use == TELNET_USE_ECHO) ? TELNET_WILL : TELNET_DO;
+ optbuf[2] = 1;
+ optbuf[3] = 0;
+ fputs((char *)optbuf, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+}
+#endif
+
+/****************************************************************************
+ * Name: nsh_telnetlogin
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_TELNET_LOGIN
+int nsh_telnetlogin(struct console_stdio_s *pstate)
+{
+ char username[16];
+ char password[16];
+ uint8_t i;
+
+ /* Present the NSH Telnet greeting */
+
+ fputs(g_telnetgreeting, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+
+ /* Loop for the configured number of retries */
+
+ for(i = 0; i < CONFIG_NSH_TELNET_FAILCOUNT; i++)
+ {
+ /* Ask for the login username */
+
+ fputs(g_userprompt, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+ if (fgets(pstate->cn_line, CONFIG_NSH_LINELEN, INSTREAM(pstate)) != NULL)
+ {
+ strcpy(username, pstate->cn_line);
+ username[strlen(pstate->cn_line) - 1] = 0;
+ }
+
+ /* Ask for the login password */
+
+ fputs(g_passwordprompt, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+ nsh_telnetecho(pstate, TELNET_NOTUSE_ECHO);
+ if (fgets(pstate->cn_line, CONFIG_NSH_LINELEN, INSTREAM(pstate)) != NULL)
+ {
+ /* Verify the username and password */
+
+ strcpy(password,pstate->cn_line);
+ password[strlen(pstate->cn_line) - 1] = 0;
+
+ if (strcmp(password, CONFIG_NSH_TELNET_PASSWORD) == 0 &&
+ strcmp(username, CONFIG_NSH_TELNET_USERNAME) == 0)
+ {
+ fputs(g_loginsuccess, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+ nsh_telnetecho(pstate, TELNET_USE_ECHO);
+ return OK;
+ }
+ else
+ {
+ fputs(g_badcredentials, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+ }
+ }
+
+ nsh_telnetecho(pstate, TELNET_USE_ECHO);
+ }
+
+ /* Too many failed login attempts */
+
+ fputs(g_loginfailure, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+ return -1;
+}
+#endif /* CONFIG_NSH_TELNET_LOGIN */
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -90,7 +188,17 @@ int nsh_telnetmain(int argc, char *argv[])
dbg("Session [%d] Started\n", getpid());
- /* Present a greeting */
+ /* Login User and Password Check */
+
+#ifdef CONFIG_NSH_TELNET_LOGIN
+ if (nsh_telnetlogin(pstate) != OK)
+ {
+ nsh_exit(&pstate->cn_vtbl, 1);
+ return -1; /* nsh_exit does not return */
+ }
+#endif /* CONFIG_NSH_TELNET_LOGIN */
+
+ /* Present the NSH greeting */
fputs(g_nshgreeting, pstate->cn_outstream);
fflush(pstate->cn_outstream);
diff --git a/apps/px4/fmu/fmu.cpp b/apps/px4/fmu/fmu.cpp
index 18f27d49e..6d990c46b 100644
--- a/apps/px4/fmu/fmu.cpp
+++ b/apps/px4/fmu/fmu.cpp
@@ -79,7 +79,7 @@ public:
FMUServo(Mode mode, int update_rate);
~FMUServo();
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+ virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual int init();
@@ -93,6 +93,7 @@ private:
int _t_armed;
orb_advert_t _t_outputs;
unsigned _num_outputs;
+ bool _primary_pwm_device;
volatile bool _task_should_exit;
bool _armed;
@@ -118,7 +119,7 @@ FMUServo *g_servo;
} // namespace
FMUServo::FMUServo(Mode mode, int update_rate) :
- CDev("fmuservo", PWM_OUTPUT_DEVICE_PATH),
+ CDev("fmuservo", "/dev/px4fmu"),
_mode(mode),
_update_rate(update_rate),
_task(-1),
@@ -126,6 +127,7 @@ FMUServo::FMUServo(Mode mode, int update_rate) :
_t_armed(-1),
_t_outputs(0),
_num_outputs(0),
+ _primary_pwm_device(false),
_task_should_exit(false),
_armed(false),
_mixers(nullptr)
@@ -135,18 +137,16 @@ FMUServo::FMUServo(Mode mode, int update_rate) :
FMUServo::~FMUServo()
{
if (_task != -1) {
-
- /* task should wake up every 100ms or so at least */
+ /* tell the task we want it to go away */
_task_should_exit = true;
- unsigned i = 0;
-
+ unsigned i = 10;
do {
- /* wait 20ms */
- usleep(20000);
+ /* wait 50ms - it should wake every 100ms or so worst-case */
+ usleep(50000);
/* if we have given up, kill it */
- if (++i > 10) {
+ if (--i == 0) {
task_delete(_task);
break;
}
@@ -154,6 +154,10 @@ FMUServo::~FMUServo()
} while (_task != -1);
}
+ /* clean up the alternate device node */
+ if (_primary_pwm_device)
+ unregister_driver(PWM_OUTPUT_DEVICE_PATH);
+
g_servo = nullptr;
}
@@ -170,6 +174,13 @@ FMUServo::init()
if (ret != OK)
return ret;
+ /* try to claim the generic PWM output device node as well - it's OK if we fail at this */
+ ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
+ if (ret == OK) {
+ log("default PWM output device");
+ _primary_pwm_device = true;
+ }
+
/* start the IO interface task */
_task = task_spawn("fmuservo",
SCHED_DEFAULT,
@@ -216,8 +227,12 @@ FMUServo::task_main()
break;
}
- /* subscribe to objects that we are interested in watching */
- _t_actuators = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
+ /*
+ * Subscribe to the appropriate PWM output topic based on whether we are the
+ * primary PWM output or not.
+ */
+ _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
+ ORB_ID(actuator_controls_1));
/* convert the update rate in hz to milliseconds, rounding down if necessary */
int update_rate_in_ms = int(1000 / _update_rate);
orb_set_interval(_t_actuators, update_rate_in_ms);
@@ -226,11 +241,13 @@ FMUServo::task_main()
orb_set_interval(_t_armed, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
- struct actuator_outputs_s outputs;
+ actuator_outputs_s outputs;
memset(&outputs, 0, sizeof(outputs));
- _t_outputs = orb_advertise(ORB_ID_VEHICLE_CONTROLS, &outputs);
+ /* advertise the mixed control outputs */
+ _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
+ &outputs);
- struct pollfd fds[2];
+ pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
fds[1].fd = _t_armed;
@@ -282,7 +299,7 @@ FMUServo::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- struct actuator_armed_s aa;
+ actuator_armed_s aa;
/* get new value */
orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
@@ -320,7 +337,7 @@ FMUServo::control_callback(uintptr_t handle,
}
int
-FMUServo::ioctl(struct file *filp, int cmd, unsigned long arg)
+FMUServo::ioctl(file *filp, int cmd, unsigned long arg)
{
int ret = OK;
int channel;
@@ -569,7 +586,7 @@ fake(int argc, char *argv[])
exit(1);
}
- struct actuator_controls_s ac;
+ actuator_controls_s ac;
ac.control[0] = strtol(argv[1], 0, 0) / 100.0f;
diff --git a/apps/px4/px4io/driver/px4io.cpp b/apps/px4/px4io/driver/px4io.cpp
index c3371c138..66db1c360 100644
--- a/apps/px4/px4io/driver/px4io.cpp
+++ b/apps/px4/px4io/driver/px4io.cpp
@@ -37,8 +37,7 @@
*
* PX4IO is connected via serial (or possibly some other interface at a later
* point).
- *
- * XXX current design is racy as all hell; need a locking strategy.
+
*/
#include <nuttx/config.h>
@@ -53,6 +52,7 @@
#include <errno.h>
#include <string.h>
#include <stdio.h>
+#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
@@ -61,185 +61,122 @@
#include <drivers/device/device.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
+#include <systemlib/mixer/mixer.h>
+#include <drivers/drv_mixer.h>
#include <systemlib/perf_counter.h>
#include <systemlib/hx_stream.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/rc_channels.h>
#include "px4io/protocol.h"
#include "uploader.h"
-class PX4IO;
-
-namespace
-{
-
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-const int ERROR = -1;
-
-PX4IO *g_dev;
-
-}
-
-
-class PX4IO_RC : public device::CDev
+class PX4IO : public device::CDev
{
public:
- PX4IO_RC();
- ~PX4IO_RC();
+ PX4IO();
+ ~PX4IO();
virtual int init();
- virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
- friend class PX4IO;
-protected:
- void set_channels(unsigned count, const servo_position_t *data);
+ virtual int ioctl(file *filp, int cmd, unsigned long arg);
private:
- orb_advert_t _publication;
- struct rc_input_values _input;
-};
+ static const unsigned _max_actuators = PX4IO_OUTPUT_CHANNELS;
-/* XXX this may conflict with the onboard PPM input */
-PX4IO_RC::PX4IO_RC() :
- CDev("px4io_rc", RC_INPUT_DEVICE_PATH),
- _publication(-1)
-{
- for (unsigned i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
- _input.values[i] = 0;
- }
- _input.channel_count = 0;
-}
+ int _serial_fd; ///< serial interface to PX4IO
+ hx_stream_t _io_stream; ///< HX protocol stream
-PX4IO_RC::~PX4IO_RC()
-{
- if (_publication != -1)
- ::close(_publication);
-}
+ int _task; ///< worker task
+ volatile bool _task_should_exit;
-int
-PX4IO_RC::init()
-{
- int ret;
+ int _t_actuators; ///< actuator output topic
+ actuator_controls_s _controls; ///< actuator outputs
- ret = CDev::init();
+ int _t_armed; ///< system armed control topic
+ actuator_armed_s _armed; ///< system armed state
- /* advertise ourselves as the RC input controller */
- if (ret == OK) {
- _publication = orb_advertise(ORB_ID(input_rc), &_input);
- if (_publication < 0)
- ret = -errno;
- }
+ orb_advert_t _t_outputs; ///< mixed outputs topic
+ actuator_outputs_s _outputs; ///< mixed outputs
- return ret;
-}
+ MixerGroup *_mixers; ///< loaded mixers
-ssize_t
-PX4IO_RC::read(struct file *filp, char *buffer, size_t buflen)
-{
- unsigned channels = buflen / sizeof(rc_input_t);
- rc_input_t *pdata = (rc_input_t *)buffer;
- unsigned i;
+ bool _primary_pwm_device; ///< true if we are the default PWM output
- if (channels > PX4IO_INPUT_CHANNELS)
- return -EIO;
+ volatile bool _switch_armed; ///< PX4IO switch armed state
+ // XXX how should this work?
- lock();
- for (i = 0; i < channels; i++)
- pdata[i] = _input.values[i];
- unlock();
+ bool _send_needed; ///< If true, we need to send a packet to IO
- return i * sizeof(servo_position_t);
-}
+ /**
+ * Trampoline to the worker task
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
-void
-PX4IO_RC::set_channels(unsigned count, const servo_position_t *data)
-{
+ /**
+ * worker task
+ */
+ void task_main();
- ASSERT(count <= PX4IO_INPUT_CHANNELS);
+ /**
+ * Handle receiving bytes from PX4IO
+ */
+ void io_recv();
- /* convert incoming servo position values into 0-100 range */
- lock();
- for (unsigned i = 0; i < count; i++) {
- rc_input_t chn;
+ /**
+ * HX protocol callback trampoline.
+ */
+ static void rx_callback_trampoline(void *arg, const void *buffer, size_t bytes_received);
- if (data[i] < 1000) {
- chn = 0;
- } else if (data[i] > 2000) {
- chn = 100;
- } else {
- chn = (data[i] - 1000) / 10;
- }
+ /**
+ * Callback invoked when we receive a whole packet from PX4IO
+ */
+ void rx_callback(const uint8_t *buffer, size_t bytes_received);
- _input.values[i] = chn;
- }
- _input.channel_count = count;
- unlock();
+ /**
+ * Send an update packet to PX4IO
+ */
+ void io_send();
- /* publish to anyone that might be listening */
- if (_publication != -1)
- orb_publish(ORB_ID(input_rc), _publication, &_input);
+ /**
+ * Mixer control callback; invoked to fetch a control from a specific
+ * group/index during mixing.
+ */
+ static int control_callback(uintptr_t handle,
+ uint8_t control_group,
+ uint8_t control_index,
+ float &input);
+};
-}
-class PX4IO : public device::CDev
+namespace
{
-public:
- PX4IO();
- ~PX4IO();
-
- virtual int init();
-
- virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen);
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
-private:
- int _fd;
- int _task;
- PX4IO_RC *_rc;
-
- /** command to be sent to IO */
- struct px4io_command _next_command;
- /** RC channel input from IO */
- servo_position_t _rc_channel[PX4IO_INPUT_CHANNELS];
- int _rc_channel_count;
-
- volatile bool _armed;
- volatile bool _task_should_exit;
-
- bool _send_needed;
-
- hx_stream_t _io_stream;
-
- static void task_main_trampoline(int argc, char *argv[]);
- void task_main();
- void io_recv();
-
- static void rx_callback_trampoline(void *arg, const void *buffer, size_t bytes_received);
- void rx_callback(const uint8_t *buffer, size_t bytes_received);
+PX4IO *g_dev;
- void io_send();
-};
+}
PX4IO::PX4IO() :
CDev("px4io", "/dev/px4io"),
- _fd(-1),
+ _serial_fd(-1),
+ _io_stream(nullptr),
_task(-1),
- _rc(new PX4IO_RC),
- _rc_channel_count(0),
- _armed(false),
_task_should_exit(false),
- _send_needed(false),
- _io_stream(nullptr)
+ _t_actuators(-1),
+ _t_armed(-1),
+ _t_outputs(-1),
+ _mixers(nullptr),
+ _primary_pwm_device(false),
+ _switch_armed(false),
+ _send_needed(false)
{
- /* set up the command we will use */
- _next_command.f2i_magic = F2I_MAGIC;
-
- /* we need this potentially before it could be set in px4io_main */
+ /* we need this potentially before it could be set in task_main */
g_dev = this;
_debug_enabled = true;
@@ -247,19 +184,18 @@ PX4IO::PX4IO() :
PX4IO::~PX4IO()
{
- if (_rc != nullptr)
- delete _rc;
if (_task != -1) {
- /* task should wake up every 100ms or so at least */
+ /* tell the task we want it to go away */
_task_should_exit = true;
- unsigned i = 0;
+ /* spin waiting for the thread to stop */
+ unsigned i = 10;
do {
- /* wait 20ms */
- usleep(20000);
+ /* wait 50ms - it should wake every 100ms or so worst-case */
+ usleep(50000);
/* if we have given up, kill it */
- if (++i > 10) {
+ if (--i == 0) {
task_delete(_task);
break;
}
@@ -267,6 +203,14 @@ PX4IO::~PX4IO()
} while (_task != -1);
}
+ /* clean up the alternate device node */
+ if (_primary_pwm_device)
+ unregister_driver(PWM_OUTPUT_DEVICE_PATH);
+
+ /* kill the HX stream */
+ if (_io_stream != nullptr)
+ hx_stream_free(_io_stream);
+
g_dev = nullptr;
}
@@ -277,17 +221,20 @@ PX4IO::init()
ASSERT(_task == -1);
- /* XXX send a who-are-you request */
-
- /* XXX verify firmware/protocol version */
-
/* do regular cdev init */
ret = CDev::init();
if (ret != OK)
return ret;
+ /* try to claim the generic PWM output device node as well - it's OK if we fail at this */
+ ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
+ if (ret == OK) {
+ log("default PWM output device");
+ _primary_pwm_device = true;
+ }
+
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_DEFAULT, 1024, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_create("px4io", SCHED_PRIORITY_DEFAULT, 4096, (main_t)&PX4IO::task_main_trampoline, nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
return -errno;
@@ -305,36 +252,61 @@ PX4IO::task_main_trampoline(int argc, char *argv[])
void
PX4IO::task_main()
{
- ASSERT(_fd == -1);
-
- log("ready");
+ log("starting");
/* open the serial port */
- _fd = ::open("/dev/ttyS2", O_RDWR | O_NONBLOCK);
- if (_fd < 0) {
+ _serial_fd = ::open("/dev/ttyS2", O_RDWR);
+ if (_serial_fd < 0) {
debug("failed to open serial port for IO: %d", errno);
_task = -1;
_exit(errno);
}
/* protocol stream */
- _io_stream = hx_stream_init(_fd, &PX4IO::rx_callback_trampoline, this);
+ _io_stream = hx_stream_init(_serial_fd, &PX4IO::rx_callback_trampoline, this);
- perf_counter_t pc_tx_bytes = perf_alloc(PC_COUNT, "PX4IO frames transmitted");
- perf_counter_t pc_rx_bytes = perf_alloc(PC_COUNT, "PX4IO frames received");
+ perf_counter_t pc_tx_frames = perf_alloc(PC_COUNT, "PX4IO frames transmitted");
+ perf_counter_t pc_rx_frames = perf_alloc(PC_COUNT, "PX4IO frames received");
perf_counter_t pc_rx_errors = perf_alloc(PC_COUNT, "PX4IO receive errors");
- hx_stream_set_counters(_io_stream, pc_tx_bytes, pc_rx_bytes, pc_rx_errors);
+ hx_stream_set_counters(_io_stream, pc_tx_frames, pc_rx_frames, pc_rx_errors);
+
+ /* XXX send a who-are-you request */
+
+ /* XXX verify firmware/protocol version */
- /* poll descriptor(s) */
- struct pollfd fds[1];
- fds[0].fd = _fd;
+ /*
+ * Subscribe to the appropriate PWM output topic based on whether we are the
+ * primary PWM output or not.
+ */
+ _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
+ ORB_ID(actuator_controls_1));
+ /* convert the update rate in hz to milliseconds, rounding down if necessary */
+ //int update_rate_in_ms = int(1000 / _update_rate);
+ orb_set_interval(_t_actuators, 20); /* XXX 50Hz hardcoded for now */
+
+ _t_armed = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+
+ /* advertise the mixed control outputs */
+ _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
+ &_outputs);
+
+ /* poll descriptor */
+ pollfd fds[3];
+ fds[0].fd = _serial_fd;
fds[0].events = POLLIN;
+ fds[1].fd = _t_actuators;
+ fds[1].events = POLLIN;
+ fds[2].fd = _t_armed;
+ fds[2].events = POLLIN;
+
+ log("ready");
/* loop handling received serial bytes */
while (!_task_should_exit) {
/* sleep waiting for data, but no more than 100ms */
- int ret = ::poll(&fds[0], 1, 100);
+ int ret = ::poll(&fds[0], sizeof(fds) / sizeof(fds[0]), 1000);
/* this would be bad... */
if (ret < 0) {
@@ -347,9 +319,36 @@ PX4IO::task_main()
if (ret == 0)
_send_needed = true;
- /* if we have new data from IO, go handle it */
- if ((ret > 0) && (fds[0].revents & POLLIN))
- io_recv();
+ if (ret > 0) {
+ /* if we have new data from IO, go handle it */
+ if (fds[0].revents & POLLIN)
+ io_recv();
+
+ /* if we have new data from the ORB, go handle it */
+ if (fds[1].revents & POLLIN) {
+
+ /* get controls */
+ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
+
+ /* mix */
+ if (_mixers != nullptr) {
+ /* XXX is this the right count? */
+ _mixers->mix(&_outputs.output[0], _max_actuators);
+
+ /* convert to PWM values */
+ for (unsigned i = 0; i < _max_actuators; i++)
+ _outputs.output[i] = 1500 + (600 * _outputs.output[i]);
+
+ /* and flag for update */
+ _send_needed = true;
+ }
+ }
+ if (fds[2].revents & POLLIN) {
+
+ orb_copy(ORB_ID(actuator_armed), _t_armed, &_controls);
+ _send_needed = true;
+ }
+ }
/* send an update to IO if required */
if (_send_needed) {
@@ -357,23 +356,40 @@ PX4IO::task_main()
io_send();
}
}
- if (_io_stream != nullptr)
- hx_stream_free(_io_stream);
- ::close(_fd);
/* tell the dtor that we are exiting */
_task = -1;
_exit(0);
}
+int
+PX4IO::control_callback(uintptr_t handle,
+ uint8_t control_group,
+ uint8_t control_index,
+ float &input)
+{
+ const actuator_controls_s *controls = (actuator_controls_s *)handle;
+
+ input = controls->control[control_index];
+ return 0;
+}
+
void
PX4IO::io_recv()
{
- uint8_t c;
-
- /* handle bytes from IO */
- while (::read(_fd, &c, 1) == 1)
- hx_stream_rx(_io_stream, c);
+ uint8_t buf[32];
+ int count;
+
+ /*
+ * We are here because poll says there is some data, so this
+ * won't block even on a blocking device. If more bytes are
+ * available, we'll go back to poll() again...
+ */
+ count = ::read(_serial_fd, buf, sizeof(buf));
+
+ /* pass received bytes to the packet decoder */
+ for (int i = 0; i < count; i++)
+ hx_stream_rx(_io_stream, buf[i]);
}
void
@@ -385,98 +401,139 @@ PX4IO::rx_callback_trampoline(void *arg, const void *buffer, size_t bytes_receiv
void
PX4IO::rx_callback(const uint8_t *buffer, size_t bytes_received)
{
- const struct px4io_report *rep = (const struct px4io_report *)buffer;
+ const px4io_report *rep = (const px4io_report *)buffer;
/* sanity-check the received frame size */
- if (bytes_received != sizeof(struct px4io_report))
+ if (bytes_received != sizeof(px4io_report))
return;
- lock();
+ /* XXX handle R/C inputs here ... needs code sharing/library */
- /* pass RC input data to the driver */
- if (_rc != nullptr)
- _rc->set_channels(rep->channel_count, &rep->rc_channel[0]);
- _armed = rep->armed;
-
- /* send an update frame */
- _send_needed = true;
+ /* remember the latched arming switch state */
+ _switch_armed = rep->armed;
unlock();
-
}
void
PX4IO::io_send()
{
- lock();
+ px4io_command cmd;
- /* send packet to IO while we're guaranteed it won't change */
- hx_stream_send(_io_stream, &_next_command, sizeof(_next_command));
+ cmd.f2i_magic = F2I_MAGIC;
- unlock();
-}
+ /* set outputs */
+ for (unsigned i = 0; i < _max_actuators; i++)
+ cmd.servo_command[i] = _outputs.output[i];
-ssize_t
-PX4IO::write(struct file *filp, const char *buffer, size_t len)
-{
- unsigned channels = len / sizeof(servo_position_t);
- servo_position_t *pdata = (servo_position_t *)buffer;
- unsigned i;
+ /* publish as we send */
+ orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &_outputs);
- if (channels > PX4IO_OUTPUT_CHANNELS)
- return -EIO;
+ // XXX relays
- lock();
- for (i = 0; i < channels; i++)
- _next_command.servo_command[i] = pdata[i];
- unlock();
+ cmd.arm_ok = _armed.armed;
- return i * sizeof(servo_position_t);
+ hx_stream_send(_io_stream, &cmd, sizeof(cmd));
}
int
-PX4IO::ioctl(struct file *filep, int cmd, unsigned long arg)
+PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
{
- int ret = -ENOTTY;
+ int ret = OK;
lock();
/* regular ioctl? */
switch (cmd) {
case PWM_SERVO_ARM:
- _next_command.arm_ok = true;
- ret = 0;
+ /* fake an armed transition */
+ _armed.armed = true;
+ _send_needed = true;
break;
case PWM_SERVO_DISARM:
- _next_command.arm_ok = false;
- ret = 0;
+ /* fake a disarmed transition */
+ _armed.armed = true;
+ _send_needed = true;
break;
- default:
- /* channel set? */
- if ((cmd >= PWM_SERVO_SET(0)) && (cmd < PWM_SERVO_SET(PX4IO_OUTPUT_CHANNELS))) {
- /* XXX sanity-check value? */
- _next_command.servo_command[cmd - PWM_SERVO_SET(0)] = arg;
- ret = 0;
- break;
+ case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1):
+ /* fake an update to the selected servo channel */
+ if ((arg >= 900) && (arg <= 2100)) {
+ _outputs.output[cmd - PWM_SERVO_SET(0)] = arg;
+ _send_needed = true;
+ } else {
+ ret = -EINVAL;
}
+ break;
- /* channel get? */
- if ((cmd >= PWM_SERVO_GET(0)) && (cmd < PWM_SERVO_GET(PX4IO_INPUT_CHANNELS))) {
- int channel = cmd - PWM_SERVO_GET(0);
+ case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1):
+ /* copy the current output value from the channel */
+ *(servo_position_t *)arg = _outputs.output[cmd - PWM_SERVO_GET(0)];
+ break;
- /* currently no data for this channel */
- if (channel >= _rc_channel_count) {
- ret = -ERANGE;
- break;
+ case MIXERIOCGETOUTPUTCOUNT:
+ *(unsigned *)arg = _max_actuators;
+ break;
+
+ case MIXERIOCRESET:
+ if (_mixers != nullptr) {
+ delete _mixers;
+ _mixers = nullptr;
+ }
+ break;
+
+ case MIXERIOCADDSIMPLE: {
+ mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
+
+ /* build the new mixer from the supplied argument */
+ SimpleMixer *mixer = new SimpleMixer(control_callback,
+ (uintptr_t)&_controls, mixinfo);
+
+ /* validate the new mixer */
+ if (mixer->check()) {
+ delete mixer;
+ ret = -EINVAL;
+
+ } else {
+ /* if we don't have a group yet, allocate one */
+ if (_mixers == nullptr)
+ _mixers = new MixerGroup(control_callback,
+ (uintptr_t)&_controls);
+
+ /* add the new mixer to the group */
+ _mixers->add_mixer(mixer);
}
- *(servo_position_t *)arg = _rc_channel[channel];
- ret = 0;
- break;
}
+ break;
+
+ case MIXERIOCADDMULTIROTOR:
+ /* XXX not yet supported */
+ ret = -ENOTTY;
+ break;
+
+ case MIXERIOCLOADFILE: {
+ MixerGroup *newmixers;
+ const char *path = (const char *)arg;
+
+ /* allocate a new mixer group and load it from the file */
+ newmixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
+ if (newmixers->load_from_file(path) != 0) {
+ delete newmixers;
+ ret = -EINVAL;
+ }
+
+ /* swap the new mixers in for the old */
+ if (_mixers != nullptr) {
+ delete _mixers;
+ }
+ _mixers = newmixers;
+
+ }
+ break;
+ default:
/* not a recognised value */
ret = -ENOTTY;
}
@@ -492,28 +549,25 @@ px4io_main(int argc, char *argv[])
{
if (!strcmp(argv[1], "start")) {
- if (g_dev != nullptr) {
- fprintf(stderr, "PX4IO: already loaded\n");
- return -EBUSY;
- }
+ if (g_dev != nullptr)
+ errx(1, "already loaded");
/* create the driver - it will set g_dev */
(void)new PX4IO;
- if (g_dev == nullptr) {
- fprintf(stderr, "PX4IO: driver alloc failed\n");
- return -ENOMEM;
- }
+ if (g_dev == nullptr)
+ errx(1, "driver alloc failed");
if (OK != g_dev->init()) {
- fprintf(stderr, "PX4IO: driver init failed\n");
delete g_dev;
- return -EIO;
+ errx(1, "driver init failed");
}
- return OK;
+ exit(0);
}
+ /* note, stop not currently implemented */
+
if (!strcmp(argv[1], "update")) {
PX4IO_Uploader *up;
const char *fn[3];
@@ -536,26 +590,19 @@ px4io_main(int argc, char *argv[])
case OK:
break;
case -ENOENT:
- fprintf(stderr, "PX4IO firmware file not found\n");
- break;
+ errx(1, "PX4IO firmware file not found");
case -EEXIST:
case -EIO:
- fprintf(stderr, "error updating PX4IO - check that bootloader mode is enabled\n");
- break;
+ errx(1, "error updating PX4IO - check that bootloader mode is enabled");
case -EINVAL:
- fprintf(stderr, "verify failed - retry the update\n");
- break;
+ errx(1, "verify failed - retry the update");
case -ETIMEDOUT:
- fprintf(stderr, "timed out waiting for bootloader - power-cycle and try again\n");
+ errx(1, "timed out waiting for bootloader - power-cycle and try again");
default:
- fprintf(stderr, "unexpected error %d\n", ret);
- break;
+ errx(1, "unexpected error %d", ret);
}
return ret;
}
-
-
- printf("need a verb, only support 'start' and 'update'\n");
- return ERROR;
+ errx(1, "need a verb, only support 'start' and 'update'");
}
diff --git a/apps/px4/px4io/driver/uploader.cpp b/apps/px4/px4io/driver/uploader.cpp
index 7d6a9e171..0fbbac839 100644
--- a/apps/px4/px4io/driver/uploader.cpp
+++ b/apps/px4/px4io/driver/uploader.cpp
@@ -318,7 +318,7 @@ PX4IO_Uploader::verify()
ret = recv(c);
if (ret != OK) {
- log("%d: got %d waiting for bytes", ret);
+ log("%d: got %d waiting for bytes", base + i, ret);
return ret;
}
diff --git a/apps/px4/tests/test_sensors.c b/apps/px4/tests/test_sensors.c
index 87ea7f058..c801869ab 100644
--- a/apps/px4/tests/test_sensors.c
+++ b/apps/px4/tests/test_sensors.c
@@ -56,10 +56,6 @@
#include "tests.h"
-#include <arch/board/drv_lis331.h>
-#include <arch/board/drv_bma180.h>
-#include <arch/board/drv_l3gd20.h>
-#include <arch/board/drv_hmc5883l.h>
#include <drivers/drv_accel.h>
/****************************************************************************
@@ -75,10 +71,6 @@
****************************************************************************/
//static int lis331(int argc, char *argv[]);
-static int l3gd20(int argc, char *argv[]);
-static int bma180(int argc, char *argv[]);
-static int hmc5883l(int argc, char *argv[]);
-static int ms5611(int argc, char *argv[]);
static int mpu6000(int argc, char *argv[]);
/****************************************************************************
@@ -90,12 +82,7 @@ struct {
const char *path;
int (* test)(int argc, char *argv[]);
} sensors[] = {
- {"bma180", "/dev/bma180", bma180},
{"mpu6000", "/dev/accel", mpu6000},
- {"l3gd20", "/dev/l3gd20", l3gd20},
- {"hmc5883l", "/dev/hmc5883l", hmc5883l},
- {"ms5611", "/dev/ms5611", ms5611},
-// {"lis331", "/dev/lis331", lis331},
{NULL, NULL, NULL}
};
@@ -107,226 +94,6 @@ struct {
* Private Functions
****************************************************************************/
-//static int
-//lis331(int argc, char *argv[])
-//{
-// int fd;
-// int16_t buf[3];
-// int ret;
-//
-// fd = open("/dev/lis331", O_RDONLY);
-// if (fd < 0) {
-// printf("\tlis331: not present on PX4FMU v1.5 and later\n");
-// return ERROR;
-// }
-//
-// if (ioctl(fd, LIS331_SETRATE, LIS331_RATE_50Hz) ||
-// ioctl(fd, LIS331_SETRANGE, LIS331_RANGE_4G)) {
-//
-// printf("LIS331: ioctl fail\n");
-// return ERROR;
-// }
-//
-// /* wait at least 100ms, sensor should have data after no more than 20ms */
-// usleep(100000);
-//
-// /* read data - expect samples */
-// ret = read(fd, buf, sizeof(buf));
-// if (ret != sizeof(buf)) {
-// printf("LIS331: read1 fail (%d)\n", ret);
-// return ERROR;
-// }
-//
-// /* read data - expect no samples (should not be ready again yet) */
-// ret = read(fd, buf, sizeof(buf));
-// if (ret != 0) {
-// printf("LIS331: read2 fail (%d)\n", ret);
-// return ERROR;
-// }
-//
-// /* XXX more tests here */
-//
-// return 0;
-//}
-
-static int
-l3gd20(int argc, char *argv[])
-{
- printf("\tL3GD20: test start\n");
- fflush(stdout);
-
- int fd;
- int16_t buf[3] = {0, 0, 0};
- int ret;
-
- fd = open("/dev/l3gd20", O_RDONLY | O_NONBLOCK);
-
- if (fd < 0) {
- printf("L3GD20: open fail\n");
- return ERROR;
- }
-
-// if (ioctl(fd, L3GD20_SETRATE, L3GD20_RATE_760HZ_LP_50HZ) ||
-// ioctl(fd, L3GD20_SETRANGE, L3GD20_RANGE_500DPS)) {
-//
-// printf("L3GD20: ioctl fail\n");
-// return ERROR;
-// } else {
-// printf("\tconfigured..\n");
-// }
-//
-// /* wait at least 100ms, sensor should have data after no more than 2ms */
-// usleep(100000);
-
-
-
- /* read data - expect samples */
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
- printf("\tL3GD20: read1 fail (%d should have been %d)\n", ret, sizeof(buf));
- //return ERROR;
-
- } else {
- printf("\tL3GD20 values #1: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
- }
-
- /* wait at least 2 ms, sensor should have data after no more than 1.5ms */
- usleep(2000);
-
- /* read data - expect no samples (should not be ready again yet) */
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
- printf("\tL3GD20: read2 fail (%d)\n", ret);
- close(fd);
- return ERROR;
-
- } else {
- printf("\tL3GD20 values #2: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
- }
-
- /* empty sensor buffer */
- ret = 0;
-
- while (ret != sizeof(buf)) {
- // Keep reading until successful
- ret = read(fd, buf, sizeof(buf));
- }
-
- /* test if FIFO is operational */
- usleep(14800); // Expecting 10 measurements
-
- ret = 0;
- int count = 0;
- bool dataready = true;
-
- while (dataready) {
- // Keep reading until successful
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
- dataready = false;
-
- } else {
- count++;
- }
- }
-
- printf("\tL3GD20: Drained FIFO with %d values (expected 8-12)\n", count);
-
- /* read data - expect no samples (should not be ready again yet) */
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != 0) {
- printf("\tL3GD20: Note: read3 got data - there should not have been data ready\n", ret);
-// return ERROR;
- }
-
- close(fd);
-
- /* Let user know everything is ok */
- printf("\tOK: L3GD20 passed all tests successfully\n");
- return OK;
-}
-
-static int
-bma180(int argc, char *argv[])
-{
- // XXX THIS SENSOR IS OBSOLETE
- // TEST REMAINS, BUT ALWAYS RETURNS OK
-
- printf("\tBMA180: test start\n");
- fflush(stdout);
-
- int fd;
- int16_t buf[3] = {0, 0, 0};
- int ret;
-
- fd = open("/dev/bma180", O_RDONLY);
-
- if (fd < 0) {
- printf("\tBMA180: open fail\n");
- return OK;
- }
-
-// if (ioctl(fd, LIS331_SETRATE, LIS331_RATE_50Hz) ||
-// ioctl(fd, LIS331_SETRANGE, LIS331_RANGE_4G)) {
-//
-// printf("BMA180: ioctl fail\n");
-// return ERROR;
-// }
-//
- /* wait at least 100ms, sensor should have data after no more than 20ms */
- usleep(100000);
-
- /* read data - expect samples */
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
- printf("\tBMA180: read1 fail (%d)\n", ret);
- close(fd);
- return OK;
-
- } else {
- printf("\tBMA180 values: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
- }
-
- /* wait at least 10ms, sensor should have data after no more than 2ms */
- usleep(100000);
-
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
- printf("\tBMA180: read2 fail (%d)\n", ret);
- close(fd);
- return OK;
-
- } else {
- printf("\tBMA180: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
- }
-
- /* empty sensor buffer */
- ret = 0;
-
- while (ret != sizeof(buf)) {
- // Keep reading until successful
- ret = read(fd, buf, sizeof(buf));
- }
-
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != 0) {
- printf("\tBMA180: Note: read3 got data - there should not have been data ready\n", ret);
- }
-
- /* Let user know everything is ok */
- printf("\tOK: BMA180 passed all tests successfully\n");
- close(fd);
-
- return OK;
-}
-
static int
mpu6000(int argc, char *argv[])
{
@@ -379,103 +146,6 @@ mpu6000(int argc, char *argv[])
return OK;
}
-static int
-ms5611(int argc, char *argv[])
-{
- printf("\tMS5611: test start\n");
- fflush(stdout);
-
- int fd;
- float buf[3] = {0.0f, 0.0f, 0.0f};
- int ret;
-
- fd = open("/dev/ms5611", O_RDONLY);
-
- if (fd < 0) {
- printf("\tMS5611: open fail\n");
- return ERROR;
- }
-
- for (int i = 0; i < 5; i++) {
- /* read data - expect samples */
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
-
- if ((int8_t)ret == -EAGAIN || (int8_t)ret == -EINPROGRESS) {
- /* waiting for device to become ready, this is not an error */
- } else {
- printf("\tMS5611: read fail (%d)\n", ret);
- close(fd);
- return ERROR;
- }
-
- } else {
-
- /* hack for float printing */
- int32_t pressure_int = buf[0];
- int32_t altitude_int = buf[1];
- int32_t temperature_int = buf[2];
-
- printf("\tMS5611: pressure:%d.%03d mbar - altitude: %d.%02d meters - temp:%d.%02d deg celcius\n", pressure_int, (int)(buf[0] * 1000 - pressure_int * 1000), altitude_int, (int)(buf[1] * 100 - altitude_int * 100), temperature_int, (int)(buf[2] * 100 - temperature_int * 100));
- }
-
- /* wait at least 10ms, sensor should have data after no more than 6.5ms */
- usleep(10000);
- }
-
- close(fd);
-
- /* Let user know everything is ok */
- printf("\tOK: MS5611 passed all tests successfully\n");
-
- return OK;
-}
-
-static int
-hmc5883l(int argc, char *argv[])
-{
- printf("\tHMC5883L: test start\n");
- fflush(stdout);
-
- int fd;
- int16_t buf[7] = {0, 0, 0};
- int ret;
-
- fd = open("/dev/hmc5883l", O_RDONLY);
-
- if (fd < 0) {
- printf("\tHMC5883L: open fail\n");
- return ERROR;
- }
-
- int i;
-
- for (i = 0; i < 5; i++) {
- /* wait at least 7ms, sensor should have data after no more than 6.5ms */
- usleep(7000);
-
- /* read data - expect samples */
- ret = read(fd, buf, sizeof(buf));
-
- if (ret != sizeof(buf)) {
- printf("\tHMC5883L: read1 fail (%d) values: x:%d\ty:%d\tz:%d\n", ret, buf[0], buf[1], buf[2]);
- close(fd);
- return ERROR;
-
- } else {
- printf("\tHMC5883L: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
- }
- }
-
- close(fd);
-
- /* Let user know everything is ok */
- printf("\tOK: HMC5883L passed all tests successfully\n");
-
- return OK;
-}
-
/****************************************************************************
* Public Functions
****************************************************************************/
diff --git a/apps/px4io/protocol.h b/apps/px4io/protocol.h
index 96e0ca350..edc2c4bd2 100644
--- a/apps/px4io/protocol.h
+++ b/apps/px4io/protocol.h
@@ -39,6 +39,8 @@
* messages and the corresponding complexity involved.
*/
+#pragma once
+
/*
* XXX MUST BE KEPT IN SYNC WITH THE VERSION IN PX4FMU UNTIL
* TREES ARE MERGED.
diff --git a/apps/system/Kconfig b/apps/system/Kconfig
index 44bf5a2e6..d4d434665 100644
--- a/apps/system/Kconfig
+++ b/apps/system/Kconfig
@@ -3,7 +3,7 @@
# see misc/tools/kconfig-language.txt.
#
-menu "Custom free memory command"
+menu "Custom Free Memory Command"
source "$APPSDIR/system/free/Kconfig"
endmenu
@@ -15,6 +15,22 @@ menu "FLASH Program Installation"
source "$APPSDIR/system/install/Kconfig"
endmenu
-menu "readline() support"
+menu "readline()"
source "$APPSDIR/system/readline/Kconfig"
endmenu
+
+menu "Power Off"
+source "$APPSDIR/system/poweroff/Kconfig"
+endmenu
+
+menu "RAMTRON"
+source "$APPSDIR/system/ramtron/Kconfig"
+endmenu
+
+menu "SD Card"
+source "$APPSDIR/system/sdcard/Kconfig"
+endmenu
+
+menu "Sysinfo"
+source "$APPSDIR/system/sysinfo/Kconfig"
+endmenu
diff --git a/apps/system/Make.defs b/apps/system/Make.defs
index a4aea2d31..3d10f84e5 100644
--- a/apps/system/Make.defs
+++ b/apps/system/Make.defs
@@ -49,3 +49,20 @@ endif
ifeq ($(CONFIG_SYSTEM_READLINE),y)
CONFIGURED_APPS += system/readline
endif
+
+ifeq ($(CONFIG_SYSTEM_POWEROFF),y)
+CONFIGURED_APPS += system/poweroff
+endif
+
+ifeq ($(CONFIG_SYSTEM_RAMTRON),y)
+CONFIGURED_APPS += system/ramtron
+endif
+
+ifeq ($(CONFIG_SYSTEM_SDCARD),y)
+CONFIGURED_APPS += system/sdcard
+endif
+
+ifeq ($(CONFIG_SYSTEM_SYSINFO),y)
+CONFIGURED_APPS += system/sysinfo
+endif
+
diff --git a/apps/system/Makefile b/apps/system/Makefile
index 73eb60d15..d64bb54c6 100644
--- a/apps/system/Makefile
+++ b/apps/system/Makefile
@@ -37,7 +37,7 @@
# Sub-directories containing system task
-SUBDIRS = free i2c install readline
+SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo
# Create the list of installed runtime modules (INSTALLED_DIRS)
diff --git a/apps/system/free/free.c b/apps/system/free/free.c
index 3d9698ecb..c44cd5e22 100644
--- a/apps/system/free/free.c
+++ b/apps/system/free/free.c
@@ -33,57 +33,65 @@
*
****************************************************************************/
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <nuttx/config.h>
#include <nuttx/progmem.h>
#include <stdio.h>
#include <stdlib.h>
-
/****************************************************************************
* Private Functions
****************************************************************************/
-
-/* \todo Max block size only works on uniform prog mem */
-
-void free_getprogmeminfo(struct mallinfo * mem)
+
+/* TODO Max block size only works on uniform prog mem */
+
+static void free_getprogmeminfo(struct mallinfo * mem)
{
- uint16_t page = 0, stpage = 0xFFFF;
- uint16_t pagesize = 0;
- int status;
-
- mem->arena = 0;
- mem->fordblks = 0;
- mem->uordblks = 0;
- mem->mxordblk = 0;
-
- for (status=0, page=0; status >= 0; page++) {
-
- status = up_progmem_ispageerased(page);
- pagesize = up_progmem_pagesize(page);
-
- mem->arena += pagesize;
-
- /* Is this beginning of new free space section */
- if (status == 0) {
- if (stpage == 0xFFFF) stpage = page;
- mem->fordblks += pagesize;
+ uint16_t page = 0, stpage = 0xFFFF;
+ uint16_t pagesize = 0;
+ int status;
+
+ mem->arena = 0;
+ mem->fordblks = 0;
+ mem->uordblks = 0;
+ mem->mxordblk = 0;
+
+ for (status=0, page=0; status >= 0; page++)
+ {
+ status = up_progmem_ispageerased(page);
+ pagesize = up_progmem_pagesize(page);
+
+ mem->arena += pagesize;
+
+ /* Is this beginning of new free space section */
+
+ if (status == 0)
+ {
+ if (stpage == 0xFFFF) stpage = page;
+ mem->fordblks += pagesize;
}
- else if (status != 0) {
- mem->uordblks += pagesize;
-
- if (stpage != 0xFFFF && up_progmem_isuniform()) {
- stpage = page - stpage;
- if (stpage > mem->mxordblk)
- mem->mxordblk = stpage;
- stpage = 0xFFFF;
+ else if (status != 0)
+ {
+ mem->uordblks += pagesize;
+
+ if (stpage != 0xFFFF && up_progmem_isuniform())
+ {
+ stpage = page - stpage;
+ if (stpage > mem->mxordblk)
+ {
+ mem->mxordblk = stpage;
+ }
+ stpage = 0xFFFF;
}
}
}
-
- mem->mxordblk *= pagesize;
-}
+ mem->mxordblk *= pagesize;
+}
/****************************************************************************
* Public Functions
diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile
index 845c149f6..00db91bb7 100644
--- a/apps/system/i2c/Makefile
+++ b/apps/system/i2c/Makefile
@@ -1,5 +1,5 @@
############################################################################
-# apps/system/i2c
+# apps/system/i2c/Makefile
#
# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/apps/system/install/install.c b/apps/system/install/install.c
index 2f11c6434..fd14b7a6f 100644
--- a/apps/system/install/install.c
+++ b/apps/system/install/install.c
@@ -33,6 +33,10 @@
*
****************************************************************************/
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <nuttx/config.h>
#include <nuttx/progmem.h>
#include <sys/stat.h>
@@ -43,9 +47,8 @@
#include <string.h>
#include <errno.h>
-
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
#define ACTION_INSTALL 0x01
@@ -55,12 +58,11 @@
#define INSTALL_PROGRAMBLOCKSIZE 1024
-
/****************************************************************************
* Private data
****************************************************************************/
-const char *install_help =
+static const char *install_help =
"Installs XIP program into flash and creates a start-up script in the\n"
"destination directory.\n\n"
"Usage:\t%s [options] source-file.xip destination-directory\n\n"
@@ -72,341 +74,397 @@ const char *install_help =
"\t--force\t\t\tReplaces existing installation\n"
"\t--start <page>\t\tInstalls application at or after <page>\n"
"\t--margin <pages>\tLeave some free space after the kernel (default 16)\n";
-
-const char *install_script_text =
+
+static const char *install_script_text =
"# XIP stacksize=%x priority=%x size=%x\n";
-
-const char *install_script_exec =
+
+static const char *install_script_exec =
"exec 0x%x\n";
-
-
+
/****************************************************************************
* Private functions
****************************************************************************/
-int install_getstartpage(int startpage, int pagemargin, int desiredsize)
+static int install_getstartpage(int startpage, int pagemargin, int desiredsize)
{
- uint16_t page = 0, stpage = 0xFFFF;
- uint16_t pagesize = 0;
- int maxlen = -1;
- int maxlen_start = 0xFFFF;
- int status;
-
- for (status=0, page=0; status >= 0; page++) {
-
- status = up_progmem_ispageerased(page);
- pagesize = up_progmem_pagesize(page);
-
- /* Is this beginning of new free space section */
- if (status == 0) {
- if (stpage == 0xFFFF) stpage = page;
+ uint16_t page = 0, stpage = 0xffff;
+ uint16_t pagesize = 0;
+ int maxlen = -1;
+ int maxlen_start = 0xffff;
+ int status;
+
+ for (status=0, page=0; status >= 0; page++)
+ {
+ status = up_progmem_ispageerased(page);
+ pagesize = up_progmem_pagesize(page);
+
+ /* Is this beginning of new free space section */
+
+ if (status == 0)
+ {
+ if (stpage == 0xffff) stpage = page;
}
- else if (status != 0) {
-
- if (stpage != 0xFFFF) {
-
- if ( (page - stpage) > maxlen) {
+ else if (status != 0)
+ {
+ if (stpage != 0xffff)
+ {
+ if ((page - stpage) > maxlen)
+ {
+ if (maxlen==-1)
+ {
+ /* First time found sth? */
+
+ stpage += pagemargin;
+ maxlen = 0;
+ }
- if (maxlen==-1) { /* First time found sth? */
- stpage += pagemargin;
- maxlen = 0;
+ if(stpage < startpage)
+ {
+ stpage = startpage;
}
-
- if(stpage < startpage)
- stpage = startpage;
-
- if (page > stpage) {
- maxlen = page - stpage;
- maxlen_start = stpage;
+
+ if (page > stpage)
+ {
+ maxlen = page - stpage;
+ maxlen_start = stpage;
}
-
- if (maxlen*pagesize >= desiredsize) {
- /* printf("Found page at %d ... %d\n", stpage, page); */
- return maxlen_start*pagesize;
+
+ if (maxlen*pagesize >= desiredsize)
+ {
+ /* printf("Found page at %d ... %d\n", stpage, page); */
+ return maxlen_start*pagesize;
}
}
-
- stpage = 0xFFFF;
+
+ stpage = 0xffff;
}
}
}
-
- /* Requested space is not available */
-
- return -1;
-}
+ /* Requested space is not available */
+
+ return -1;
+}
-int install_programflash(int startaddr, const char *source)
+static int install_programflash(int startaddr, const char *source)
{
- int status;
- int count;
- int totalsize = 0;
- char *buf;
- FILE *fp;
-
- if ( (buf = malloc(INSTALL_PROGRAMBLOCKSIZE)) == NULL )
- return -errno;
-
- if ( (fp=fopen(source, "r")) ) {
- do {
- count = fread(buf, 1, INSTALL_PROGRAMBLOCKSIZE, fp);
-
- if ( (status = up_progmem_write(startaddr, buf, count)) < 0) {
- totalsize = status;
- break;
+ int status;
+ int count;
+ int totalsize = 0;
+ char *buf;
+ FILE *fp;
+
+ if ((buf = malloc(INSTALL_PROGRAMBLOCKSIZE)) == NULL)
+ {
+ return -ENOMEM;
+ }
+
+ if ((fp = fopen(source, "r")))
+ {
+ do
+ {
+ count = fread(buf, 1, INSTALL_PROGRAMBLOCKSIZE, fp);
+
+ if ((status = up_progmem_write(startaddr, buf, count)) < 0)
+ {
+ totalsize = status;
+ break;
}
-
- startaddr += count;
- totalsize += count;
+
+ startaddr += count;
+ totalsize += count;
}
- while(count);
+ while(count);
+ }
+ else
+ {
+ totalsize = -errno;
}
- else totalsize = -errno;
-
- fclose(fp);
- free(buf);
-
- return totalsize;
-}
+ fclose(fp);
+ free(buf);
-void install_getscriptname(char *scriptname, const char *progname, const char *destdir)
-{
- const char * progonly;
-
- /* I.e. as /usr/bin */
- strcpy(scriptname, destdir);
-
- /* extract from i.e. /sdcard/demo -> /demo, together with / */
- progonly = strrchr(progname, '/');
- strcat(scriptname, progonly);
+ return totalsize;
}
-
-int install_getprogsize(const char *progname)
+static void install_getscriptname(char *scriptname, const char *progname, const char *destdir)
{
- struct stat fileinfo;
-
- if ( stat(progname, &fileinfo) < 0 )
- return -1;
-
- return fileinfo.st_size;
+ const char * progonly;
+
+ /* I.e. as /usr/bin */
+
+ strcpy(scriptname, destdir);
+
+ /* extract from i.e. /sdcard/demo -> /demo, together with / */
+
+ progonly = strrchr(progname, '/');
+ strcat(scriptname, progonly);
}
+static int install_getprogsize(const char *progname)
+{
+ struct stat fileinfo;
+
+ if (stat(progname, &fileinfo) < 0)
+ {
+ return -1;
+ }
+
+ return fileinfo.st_size;
+}
-int install_alreadyexists(const char *scriptname)
+static int install_alreadyexists(const char *scriptname)
{
- FILE *fp;
-
- if ( (fp=fopen(scriptname, "r"))==NULL )
- return 0;
-
- fclose(fp);
+ FILE *fp;
+
+ if ((fp = fopen(scriptname, "r")) == NULL)
+ {
+ return 0;
+ }
+
+ fclose(fp);
return 1;
}
-
-int install_createscript(int addr, int stacksize, int progsize,
- int priority, const char *scriptname)
+static int install_createscript(int addr, int stacksize, int progsize,
+ int priority, const char *scriptname)
{
- FILE *fp;
-
- if ( (fp=fopen(scriptname, "w+"))==NULL )
- return -errno;
-
- fprintf(fp, install_script_text, stacksize, priority, progsize);
- fprintf(fp, install_script_exec, addr);
-
- fflush(fp);
- fclose(fp);
-
- return 0;
-}
+ FILE *fp;
+
+ if ((fp = fopen(scriptname, "w+")) == NULL)
+ {
+ return -errno;
+ }
+ fprintf(fp, install_script_text, stacksize, priority, progsize);
+ fprintf(fp, install_script_exec, addr);
-int install_getlasthexvalue(FILE *fp, char delimiter)
+ fflush(fp);
+ fclose(fp);
+
+ return 0;
+}
+
+static int install_getlasthexvalue(FILE *fp, char delimiter)
{
- char buf[128];
- char *p;
-
- if (fgets(buf, 127, fp)) {
- if ( (p = strrchr(buf, delimiter)) ) {
- return strtol(p+1, NULL, 16);
+ char buf[128];
+ char *p;
+
+ if (fgets(buf, 127, fp))
+ {
+ if ((p = strrchr(buf, delimiter)))
+ {
+ return strtol(p+1, NULL, 16);
}
}
- return -1;
-}
+ return -1;
+}
-int install_remove(const char *scriptname)
+static int install_remove(const char *scriptname)
{
- FILE *fp;
- int progsize, addr, freedsize;
- uint16_t page;
- int status = 0;
-
- /* Parse script */
-
- if ( (fp=fopen(scriptname, "r")) ) {
- progsize = install_getlasthexvalue(fp,'=');
- addr = install_getlasthexvalue(fp,' ');
- freedsize = progsize;
+ FILE *fp;
+ int progsize, addr, freedsize;
+ uint16_t page;
+ int status = 0;
+
+ /* Parse script */
+
+ if ((fp = fopen(scriptname, "r")))
+ {
+ progsize = install_getlasthexvalue(fp,'=');
+ addr = install_getlasthexvalue(fp,' ');
+ freedsize = progsize;
+ }
+ else
+ {
+ return -errno;
+ }
+
+ fclose(fp);
+
+ /* Remove pages */
+
+ if (progsize <= 0 || addr <= 0)
+ {
+ return -EIO;
}
- else return -errno;
-
- fclose(fp);
-
- /* Remove pages */
-
- if (progsize <= 0 || addr <= 0)
- return -EIO;
-
- do {
- if ((page = up_progmem_getpage(addr)) < 0) {
- status = -page;
- break;
+
+ do
+ {
+ if ((page = up_progmem_getpage(addr)) < 0)
+ {
+ status = -page;
+ break;
}
-
- if ( up_progmem_erasepage(page) < 0) {
- status = -page;
- break;
+
+ if (up_progmem_erasepage(page) < 0)
+ {
+ status = -page;
+ break;
}
-
- addr += up_progmem_pagesize(page);
- progsize -= up_progmem_pagesize(page);
-
- } while(progsize > 0);
-
- if (status < 0) return status;
-
- /* Remove script file */
-
- if (unlink(scriptname) < 0) return -errno;
-
- return freedsize;
+
+ addr += up_progmem_pagesize(page);
+ progsize -= up_progmem_pagesize(page);
+
+ }
+ while(progsize > 0);
+
+ if (status < 0)
+ {
+ return status;
+ }
+
+ /* Remove script file */
+
+ if (unlink(scriptname) < 0)
+ {
+ return -errno;
+ }
+
+ return freedsize;
}
/****************************************************************************
- * Start
+ * Public Functions
****************************************************************************/
int install_main(int argc, char *argv[])
{
- int i;
- int progsize;
- int scrsta;
- int stacksize = 4096;
- int priority = SCHED_PRIORITY_DEFAULT;
- int pagemargin = 16;
- int startpage = 0;
- int startaddr = 0;
- int action = ACTION_INSTALL;
- char scriptname[128];
-
- /* Supported? */
-
- if ( !up_progmem_isuniform() ) {
- fprintf(stderr, "Error: install supports uniform organization only.\n");
- return -1;
+ int i;
+ int progsize;
+ int scrsta;
+ int stacksize = 4096;
+ int priority = SCHED_PRIORITY_DEFAULT;
+ int pagemargin = 16;
+ int startpage = 0;
+ int startaddr = 0;
+ int action = ACTION_INSTALL;
+ char scriptname[128];
+
+ /* Supported? */
+
+ if (!up_progmem_isuniform())
+ {
+ fprintf(stderr, "Error: install supports uniform organization only.\n");
+ return -1;
}
-
- /* Parse arguments */
-
- for (i=1; i<argc; i++) {
- if (argv[i][0]=='-' && argv[i][1]=='-' && i<=argc) {
-
- if (strcmp(argv[i]+2, "stack")==0) {
- stacksize = atoi(argv[++i]);
+
+ /* Parse arguments */
+
+ for (i=1; i<argc; i++)
+ {
+ if (argv[i][0]=='-' && argv[i][1]=='-' && i<=argc)
+ {
+ if (strcmp(argv[i]+2, "stack")==0)
+ {
+ stacksize = atoi(argv[++i]);
}
- else if (strcmp(argv[i]+2, "priority")==0) {
- priority = atoi(argv[++i]);
+ else if (strcmp(argv[i]+2, "priority")==0)
+ {
+ priority = atoi(argv[++i]);
}
- else if (strcmp(argv[i]+2, "start")==0) {
- startpage = atoi(argv[++i]);
+ else if (strcmp(argv[i]+2, "start")==0)
+ {
+ startpage = atoi(argv[++i]);
}
- else if (strcmp(argv[i]+2, "margin")==0) {
- pagemargin = atoi(argv[++i]);
+ else if (strcmp(argv[i]+2, "margin")==0)
+ {
+ pagemargin = atoi(argv[++i]);
}
- else if (strcmp(argv[i]+2, "remove")==0) {
- action = ACTION_REMOVE;
+ else if (strcmp(argv[i]+2, "remove")==0)
+ {
+ action = ACTION_REMOVE;
}
- else if (strcmp(argv[i]+2, "force")==0) {
- action = ACTION_REINSTALL;
+ else if (strcmp(argv[i]+2, "force")==0)
+ {
+ action = ACTION_REINSTALL;
}
- else fprintf(stderr, "Unknown option: %s\n", argv[i]);
+ else fprintf(stderr, "Unknown option: %s\n", argv[i]);
+ }
+ else
+ {
+ break;
}
- else break;
}
-
- /* Do the job */
-
- switch(action & 1) {
-
- case ACTION_REMOVE:
- if (i > argc-1) {
- action = ACTION_INSUFPARAM;
- break; /* are there sufficient parameters */
- }
- if ( (scrsta=install_remove(argv[i])) < 0) {
- fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta) );
+
+ /* Do the job */
+
+ switch(action & 1)
+ {
+ case ACTION_REMOVE:
+ if (i > argc-1)
+ {
+ action = ACTION_INSUFPARAM;
+ break; /* are there sufficient parameters */
+ }
+
+ if ((scrsta=install_remove(argv[i])) < 0)
+ {
+ fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta));
+ return -1;
+ }
+
+ printf("Removed %s and freed %d bytes\n", argv[i], scrsta);
+ return 0;
+
+ case ACTION_INSTALL:
+ if (i > argc-2)
+ {
+ action = ACTION_INSUFPARAM;
+ break; /* are there sufficient parameters */
+ }
+
+ install_getscriptname(scriptname, argv[i], argv[i+1]);
+
+ /* script-exists? */
+
+ if (install_alreadyexists(scriptname) == 1)
+ {
+ if (action != ACTION_REINSTALL)
+ {
+ fprintf(stderr, "Program with that name already exists.\n");
+ return -EEXIST;
+ }
+
+ if ((scrsta = install_remove(scriptname)) < 0)
+ {
+ fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta));
return -1;
- }
- printf("Removed %s and freed %d bytes\n", argv[i], scrsta);
- return 0;
-
-
- case ACTION_INSTALL:
- if (i > argc-2) {
- action = ACTION_INSUFPARAM;
- break; /* are there sufficient parameters */
- }
-
- install_getscriptname(scriptname, argv[i], argv[i+1]);
-
- // script-exists?
- if (install_alreadyexists(scriptname)==1) {
-
- if (action != ACTION_REINSTALL) {
- fprintf(stderr, "Program with that name already exists.\n");
- return -EEXIST;
- }
-
- if ( (scrsta=install_remove(scriptname)) < 0) {
- fprintf(stderr, "Could not remove program: %s\n", strerror(-scrsta) );
- return -1;
- }
-
- printf("Replacing %s\n", scriptname);
- }
-
- startaddr = install_getstartpage(startpage, pagemargin, install_getprogsize(argv[i]) );
- if (startpage < 0) {
- fprintf(stderr, "Not enough memory\n");
- return -ENOMEM;
- }
-
- if ( (progsize = install_programflash(startaddr, argv[i])) <= 0) {
- fprintf(stderr, "Error writing program memory: %s\n"
+ }
+
+ printf("Replacing %s\n", scriptname);
+ }
+
+ startaddr = install_getstartpage(startpage, pagemargin, install_getprogsize(argv[i]));
+ if (startpage < 0)
+ {
+ fprintf(stderr, "Not enough memory\n");
+ return -ENOMEM;
+ }
+
+ if ((progsize = install_programflash(startaddr, argv[i])) <= 0)
+ {
+ fprintf(stderr, "Error writing program memory: %s\n"
"Note: Flash pages are not released, so you may try again and program will be\n"
- " written in other pages.\n", strerror(-progsize) );
-
- return -EIO;
- }
- if ( (scrsta = install_createscript(startaddr, stacksize, progsize,
- priority, scriptname)) < 0) {
- fprintf(stderr, "Error writing program script at %s: %s\n",
- argv[i+1], strerror(-scrsta) );
- return -EIO;
- }
-
- printf("Installed application of size %d bytes to program memory [%xh - %xh].\n",
+ " written in other pages.\n", strerror(-progsize));
+ return -EIO;
+ }
+
+ if ((scrsta = install_createscript(startaddr, stacksize, progsize,
+ priority, scriptname)) < 0)
+ {
+ fprintf(stderr, "Error writing program script at %s: %s\n",
+ argv[i+1], strerror(-scrsta));
+ return -EIO;
+ }
+
+ printf("Installed application of size %d bytes to program memory [%xh - %xh].\n",
progsize, startaddr, startaddr + progsize);
-
- return 0;
+ return 0;
}
-
- fprintf(stderr, install_help, argv[0], argv[0]);
- return -1;
+
+ fprintf(stderr, install_help, argv[0], argv[0]);
+ return -1;
}
diff --git a/apps/system/readline/readline.c b/apps/system/readline/readline.c
index ec2dc1c0a..f64049ed7 100644
--- a/apps/system/readline/readline.c
+++ b/apps/system/readline/readline.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * lib/stdio/lib_fgets.c
+ * apps/system/readline/readline.c
*
* Copyright (C) 2007-2008, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/apps/systemcmds/top/top.c b/apps/systemcmds/top/top.c
index e6248dd43..f4e260211 100644
--- a/apps/systemcmds/top/top.c
+++ b/apps/systemcmds/top/top.c
@@ -135,9 +135,9 @@ int top_main(int argc, char *argv[])
memset(header_spaces, ' ', CONFIG_TASK_NAME_SIZE);
header_spaces[CONFIG_TASK_NAME_SIZE] = '\0';
#if CONFIG_RR_INTERVAL > 0
- printf("\033[KPID\tCOMMAND%s CPU TOTAL \t%%CPU CURR \tMIN STACK USE\tCURR (BASE) PRIO\tRR SLICE\n", header_spaces);
+ printf("\033[KPID\tCOMMAND%s CPU TOTAL \t%%CPU CURR \tSTACK USE\tCURR (BASE) PRIO\tRR SLICE\n", header_spaces);
#else
- printf("\033[KPID\tCOMMAND%s CPU TOTAL \t%%CPU CURR \tMIN STACK USE\tCURR (BASE) PRIO\n", header_spaces);
+ printf("\033[KPID\tCOMMAND%s CPU TOTAL \t%%CPU CURR \tSTACK USE\tCURR (BASE) PRIO\n", header_spaces);
#endif
} else {
@@ -190,7 +190,26 @@ int top_main(int argc, char *argv[])
runtime_spaces = "";
}
- printf("\033[K % 2d\t%s%s % 8lld ms%s \t % 2d.%03d \t % 6d B", (int)system_load.tasks[i].tcb->pid, system_load.tasks[i].tcb->name, spaces, (system_load.tasks[i].total_runtime / 1000), runtime_spaces, (int)(curr_loads[i] * 100), (int)(curr_loads[i] * 100000.0f - (int)(curr_loads[i] * 1000.0f) * 100), (uint32_t)system_load.tasks[i].tcb->adj_stack_ptr - (uint32_t)system_load.tasks[i].tcb->xcp.regs[REG_R13]);
+ unsigned stack_size = (uintptr_t)system_load.tasks[i].tcb->adj_stack_ptr -
+ (uintptr_t)system_load.tasks[i].tcb->stack_alloc_ptr;
+ unsigned stack_free = 0;
+ uint8_t *stack_sweeper = (uint8_t *)system_load.tasks[i].tcb->stack_alloc_ptr;
+ while (stack_free < stack_size) {
+ if (*stack_sweeper++ != 0xff)
+ break;
+ stack_free++;
+ }
+
+ printf("\033[K % 2d\t%s%s % 8lld ms%s \t % 2d.%03d \t % 4u / % 4u",
+ (int)system_load.tasks[i].tcb->pid,
+ system_load.tasks[i].tcb->name,
+ spaces,
+ (system_load.tasks[i].total_runtime / 1000),
+ runtime_spaces,
+ (int)(curr_loads[i] * 100),
+ (int)(curr_loads[i] * 100000.0f - (int)(curr_loads[i] * 1000.0f) * 100),
+ stack_size - stack_free,
+ stack_size);
/* Print scheduling info with RR time slice */
#if CONFIG_RR_INTERVAL > 0
printf("\t%d\t(%d)\t\t%d\n", (int)system_load.tasks[i].tcb->sched_priority, (int)system_load.tasks[i].tcb->base_priority, (int)system_load.tasks[i].tcb->timeslice);
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index adb52afce..a8e045616 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3177,7 +3177,7 @@
* arch/arm/src/stm32/stm32_otgfshost.c: This driver now appears to be
functional (although more testing is necesary).
-6.22 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+6.22 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
* include/semaphore.h, sched/sem_holders.c, and lib/semaphore/sem_init.c:
Fix some strange (and probably wrong) list handling when
@@ -3193,7 +3193,7 @@
speed/duplex. This does not work for certain PHYs. Still some unresolved
issues (also from Kate).
* tools/Config.mk, Makefile, configs/*/Make.defs: Add a new Makefile
- fragement to de-quoate certain strings from the Kconfig logic that
+ fragment to de-quote certain strings from the Kconfig logic that
need to be used at path segments (Richard Cochran).
* arch/arm/src/stm32/stm32_usbotghost.c: The STM32 USB host driver only
works with debug turned on. The problem appears to be that with debug
@@ -3201,7 +3201,7 @@
reveals a variety of errors. This check in improves NAK robustness
for control transfers but does not resolve all of the issues.
* configs/stm3220g-eval/*/defconfig: Calibrated delay loop. It had
- never been calibrated was was way off.
+ never been calibrated was way off.
* sched/sem_holder.c: Add logic to handler some priority inheritance
cases when sem_post() is called from an interrupt handler. The
logic is clearly wrong, but it is not known if this is the
@@ -3212,13 +3212,13 @@
CONFIG_LIBC_STRERROR_SHORT that can be used to output shortened
strings by strerror().
* arch/arm/src/stm32/stm32_usbotghost.c: Finally... the USB OTG FS
- appears to handle NAKing correctly is complete.
+ appears to handle NAKing correctly.
* configs/stm32f4discovery/*: Added and verifed support for USB OTG FS
host on the STM32F4Discovery board.
* configs/*/defconfig: Remove configuration documentation from config
files. It is redundant, error-prone, and difficult to maintain.
Configuration documentation is available in configs/README.txt for
- common configurations and in configs/*/README.txt for board and MCU_
+ common configurations and in configs/*/README.txt for board and MCU-
specific configurations.
* configs/stm3240g-eval: Add USB host support.
* sched/os_bring.c, configs/*/defconfig, tools/mkconfig.c, and others: Added
@@ -3226,7 +3226,7 @@
the default entry from user_start to some other symbol. Contributed by
Kate. NOTE: This change does introduce a minor backward incompatibility.
For example, if your application uses NSH as its start-up program, then your
- code will not fail because it will be unable to find "user_start". The fix
+ build will now fail because it will be unable to find "user_start". The fix
for this link failure is to add the following to your configuration file:
CONFIG_USER_ENTRYPOINT="nsh_main".
* libs/stdio/lib_libfread.c and lib_*flush*.c: Correct a couple of
@@ -3269,7 +3269,7 @@
CONFIG_HEAP2_SIZE (decimal) instead of CONFIG_HEAP2_END (hex).
* tools/configure.sh: Don't append the apps directory path setting
if the correct setting is already in defined in the defconfig file.
- * fs/fat/fs_utils.c: Improper constructed bool expression. This
+ * fs/fat/fs_utils.c: Improperly constructed bool expression. This
would cause many unnecessary writes to FLASH (Thanks Ronen Vainish).
* Kconfig: Verify configuration settings for the LPC43xx. This includes
some corrections to configuration variable names and defconfig settings.
@@ -3319,13 +3319,13 @@
in all places.
* drivers/enc28j60.c, include/nuttx/net/enc28j60.h, and
olimex-strp711/src/up_enc28j60.c: No longer passes IRQ number
- as a parameters. Instead now passes a call table to manage
+ as a parameter. Instead now passes a call table to manage
ENC28J60 GPIO interrupts. That is because GPIO interrupts are
handled in different ways by different MCUs and some do not
support IRQ numbers for GPIO interrupts.
* mm/mm_gran* and include/nuttx/gran.h: Add a simple granule-
based allocator. The intent of this allocator is to support
- simple allocation of DMA I/O buffers. The initiali check-in
+ simple allocation of DMA I/O buffers. The initial check-in
is code complete but untested (not event built into the
mm/Makefile yet.
* confgs/fire-stm32v2: The board port is basically functional.
@@ -3352,7 +3352,7 @@
* arch/arm/include/armv7-m/irq.h: Fix a critical bug in irqsave().
It looks like sometimes the compile will re-order some instructions
inapproapriately. This end result is that interrupts will get
- stuff off.
+ stuck off.
* drivers/mtd/w25.c: Beginning of a driver for the Windbond SPI
FLASH family (W25x16, W25x32, and W25x64). The initial check-in
is basically just the SST25 driver with some name changes.
@@ -3372,7 +3372,7 @@
I2C reset logic to recover from locked devices on the bus.
* configs/*/*/Make.defs, tools/Config.mk, Makefile: Refactor all
common make definitions from the various Make.defs files into
- the common tools/Make.mk. Add support for a verbosity options:
+ the common tools/Config.mk. Add support for a verbosity options:
Specify V=1 on the make command line in order to see the exact
commands used in the build (Contributed by Richard Cochran).
* drivers/net/enc28j60.c: The ENC28J60 Ethernet driver is
@@ -3400,17 +3400,17 @@
* configs/shenzhou/src/up_lcd.c: Oops. Shenzhou LCD does not
have an SSD1289 controller. Its an ILI93xx. Ported the
STM3240G-EVAL ILI93xx driver to work on the Shenzhou board.
- * configs/shenzhou/nxwm: Added an NxWM configuratino for the
+ * configs/shenzhou/nxwm: Added an NxWM configuration for the
Shenzhou board. This is untested on initial check-in. It will
be used to verify the Shenzhou LCD driver (and eventually the
touchscreen driver).
* configs/shenzhou/src/up_touchscreen.c: Add ADS7843E touchscreen
support for the Shenzhou board. The initial check-in is untested
- and basically a clone of the the touchscreen support fro the SAM-3U.
+ and basically a clone of the the touchscreen support for the SAM-3U.
* tools/cfgparser.c: There are some NxWidget configuration
settings that must be de-quoted.
* arch/arm/src/stm32/Kconfig: There is no SPI4. Some platforms
- SPI3 and some do not (still not clear).
+ support SPI3 and some do not (still not clear).
* nuttx/configs/shenzhou: Various fixes to build new NxWM
configuration.
* configs/shenzhou: Oops. The Shenzhou LCD is and SSD1289,
@@ -3419,4 +3419,55 @@
on the Shenzhou board.
* graphics/nxmu: Correct some bad parameter checking that caused
failures when DEBUG was enabled.
+ * arch/arm/src/armv7-m/nvic.h: Add bit definitions for the AIRCR
+ register.
+ * drivers/input/ads7843.c: Need semaphore protection in logic
+ that samples the position.
+ * drivers/lcd/ssd1289.c: On some platforms we are unable to
+ read the device ID -- reason unknown; workaround in place.
+ * drivers/input/ads7843.c: Add thresholding options and an
+ option to swap X and Y positions. Fix some logic errors in
+ the SPI locking/selecting logic.
+ * arch/arm/src/armv7-m/up_systemreset.c: Add logic to reset
+ the Cortex-Mx using the AIRCR register. Contributed by Darcy
+ Gong.
+ * arch/arm/src/stm32/up_eth.c: Add logic specifically for the
+ DM9161 PHY. If the DM9161 failed to initialize, then use the
+ up_sysemreset() logic to reset the MCU. Contributed by Darcy
+ Gong.
+ * arch/arm/src/stm32/stm32_gpio.c: Add missing logic to set bit
+ for SPI3 remap. This fixes the XPT2046 touchscreen driver using
+ drivers/input/ads7843.c
+ * configs/shenzhou/src/up_ssd1289.c: Fix naming error in
+ conditional compilation.
+ * configs/shenzhou/nxwm/defconfig: Disable reading from the LCD.
+ This does not work. The hardware and the driver support the
+ capability, but there is some bug that causes memory corruption.
+ The work around for now: Just disable reading from the LCD.
+ * drivers/lcd/ssd1289.c: Add some logic to reduce the amount of
+ output when CONFIG_DEBUG_LCD is enabled.
+ * configs/shenzhou/nxwm/defconfig: Bug found and fixed... The
+ original configuration had too much stuff turned on. Reducing
+ stack sizes, some features, and buffer sizes made the
+ configuration reliable (Reading from the LCD is still disabled).
+ * net/uip/uip_icmpping.c: Fix problem that prevented ping from
+ going outside of local network. Submitted by Darcy Gong
+
+6.23 2012-09-29 Gregory Nutt <gnutt@nuttx.org>
+
+ * arch/arm/src/stm32/stm32_rng.c, chip/stm32_rng.h, and other files:
+ Implementation of /dev/random using the STM32 Random Number
+ Generator (RNG).
+ * board.h file for shenzhou, fire-stm32v2, and olimex-stm32-p107:
+ Add frequencies for HSE, HSI, LSE, and LSI. These are needed
+ by the STM32 watchdog driver.
+ * CONFIG_EXAMPLES_*: To make things consistent, changed all occurrences
+ of CONFIG_EXAMPLE_* to CONFIG_EXAMPLES_*.
+ * drivers/mtd/w25.c and configs/*/src/up_w25.c: Several fixes for the
+ W25 SPI FLASH.
+ * configs/*/Make.defs: All buildroot tools now use the extension
+ xxx-nuttx-elf- vs. xxx-elf-
+ * configs/shenzhou/*/Make.defs: Now uses the new buildroot 4.6.3
+ EABI toolchain.
+ * lib/stdio/lib_libdtoa.c: Another dtoa() fix from Mike Smith.
diff --git a/nuttx/README.txt b/nuttx/README.txt
index 7477e0a24..d60da2d88 100644
--- a/nuttx/README.txt
+++ b/nuttx/README.txt
@@ -853,9 +853,8 @@ apps
|- system/
| |- i2c/README.txt
| |- free/README.txt
- | `- install
- | `- README.txt
- |- vsn/
+ | |- install
+ | | `- README.txt
| |- poweroff
| | `- README.txt
| |- ramtron
diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes
index 4d7211669..b1d5f6064 100644
--- a/nuttx/ReleaseNotes
+++ b/nuttx/ReleaseNotes
@@ -1606,6 +1606,8 @@ The 61st release of NuttX, NuttX-5.14, was made on November 27,
2010. This release includes multiple, important bugfixes as well
as a new driver for the NXP LPC1766.
+This release corresponds with SVN release number: r3137
+
Important bugfixes include:
* Cortex-M3 Hard Fault. Fixed a hard fault problem that can occur
@@ -2052,6 +2054,8 @@ interest expressed by members of the forum and because of the
availability of newer, larger capacity AVR parts (that I don't have
yet).
+This release corresponds with SVN release number: r3730
+
This release includes support for the following AVR boards. As
with any initial support for new architectures, there are some
incomplete areas and a few caveats that need to be stated. Here
@@ -3063,3 +3067,107 @@ Bugfixes (see the change log for details) :
for C++
As well as other, less critical bugs (see the ChangeLog for details)
+
+NuttX-6.22
+^^^^^^^^^^
+
+The 89th release of NuttX, Version 6.22, was made on September 29, 2012,
+and is available for download from the SourceForge website. Note
+that release consists of two tarballs: nuttx-6.22.tar.gz and
+apps-6.22.tar.gz. Both may be needed (see the top-level nuttx/README.txt
+file for build information).
+
+This release corresponds with SVN release number: r5206
+
+Note that all SVN information has been stripped from the tarballs. If you
+need the SVN configuration, you should check out directly from SVN. Revision
+r5206 should equivalent to release 6.22 of NuttX 6.22:
+
+ svn checkout -r5206 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
+
+Or
+
+ svn checkout -r5206 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
+
+Additional new features and extended functionality:
+
+ * RTOS: Application entry point is no longer user_start, but can be
+ configured using CONFIG_USER_ENTRYPOINT. NuttX now supports two work
+ queues: A lower priority work queue (for extended processing) and a
+ higher priority work queue (for quick, high priority operations).
+
+ * Memory Management: Added a new granule-based allocated that can be
+ used to manage, aligned and quantized DMA memory.
+
+ * File System: Add hooks to allocate I/O memory with and external
+ allocated (need if required by DMA).
+
+ * Networking: ENC28J60 driver is (finally) verified.
+
+ * Drivers: Add hooks USB device drivers to allocate I/O memory with and
+ external allocated (need if required by DMA). Driver for the Windbond
+ SPI FLASH family (W25x16, W25x32, W25x64, and others). ADS7843E driver
+ extended for TSC2046 and XPT2046 and verified.
+
+ * ARMv7-M: Added logic to reset the MCU using the NVIC.
+
+ * STM32: Add support for STM32F103VET6.
+
+ * STM32 Drivers: Add logic to re-initialize UARTs a second time to
+ enable DMA (Mike Smith). I2C driver error recovery (Mike Smith).
+
+ * STM32 boards: Support for USB host added add to several configurations
+ (or at least explained in README files). Support for the Shenzhou
+ STM32F107 board (see www.armjishu.com). Support for M3 Wildfire
+ STM32F103 board (v2 and v3).
+
+ * Build System: Kconfig string de-quoting logic. Remove comments from
+ defconfig files (Kate). Add tool to create NuttX-style symbol tables.
+ Numerous changes to configuration logic as needed for the new mconf-based
+ configuration (much of this from Richard Cochran). Refactor common
+ Make.defs logic into tools/Config.mk (Richard Cochran).
+
+ * Library: Configurable terse output from strerror(). Added perror() (Kate).
+ Add %n format to sscanf() (Kate).
+
+ * Applications: Numerous changes and extensions to the old uIP web server
+ (from Kate and Max Holtzberg, see the ChangeLog for specific extensions).
+ UDP network discovery utility (Max Holtzberg). Embeddable Lightweight
+ XML-RPC Server (http://www.drdobbs.com/web-development/an-embeddable-lightweight-xml-rpc-server/184405364, Max Holtzberg).
+
+Bugfixes (see the change log for details). Some of these are very important
+(marked *critical*):
+
+ * RTOS: Fixes to priority inheritance logic (*critical*). waitpid()
+ critical section. Assertion in work_cancel() (Mike Smith). mmap() (Kate).
+
+ * FAT File System: Improper Boolean expression caused un-necessary writes
+ and performance issues (*critical*, Ronen Vainish).
+
+ * Networking: Remove an un-necessary delay from recvfrom(). This greatly
+ improves network performance (*critical*, Max Holtzberg).
+
+ * Graphics: NX parameter checking errors.
+
+ * Drivers: Fix double release of memory in SDIO-based, MMC/SD driver
+ (Ronen Vainish).
+
+ * LPC17xx: Ethernet driver fixes needed for certain PHYs (Kate).
+
+ * AVR: Fix build error (Richard Cochran).
+
+ * STM32: USB OTG FS host driver NAKing an retries. Power management
+ compilation errors (Diego Sanchez). Missing SPI3 remap logic.
+
+ * STM32 Drivers: Fix for Ethernet errata for STM32F107 (*critical*).
+ Ethernet buffer alignment check. Add "kludge" to Ethernet driver to
+ handle DM9161 PHY which (at least on the Shenzhou board), sometimes
+ does not come up correctly.
+
+ * Applications: THTTPD (Kate). NSH ping when IP address is on a different
+ network (Darcy Gong).
+
+ * Library: fread(), fflush(), fdopen(): Fix error handling logic (Ronen
+ Vainish). Fix some field-width handling issues in sscanf()
+
+As well as other, less critical bugs (see the ChangeLog for details)
diff --git a/nuttx/TODO b/nuttx/TODO
index 72a94290b..906601192 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -12,7 +12,7 @@ nuttx/
(2) Signals (sched/, arch/)
(2) pthreads (sched/)
(2) C++ Support
- (5) Binary loaders (binfmt/)
+ (6) Binary loaders (binfmt/)
(17) Network (net/, drivers/net)
(3) USB (drivers/usbdev, drivers/usbhost)
(11) Libraries (lib/)
@@ -376,15 +376,15 @@ o Binary loaders (binfmt/)
Description: Windows build issue. Some of the configurations that use NXFLAT have
the linker script specified like this:
- NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+ NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld -no-check-sections
That will not work for windows-based tools because they require Windows
style paths. The solution is to do something like this:
if ($(WINTOOL)y)
- NXFLATLDSCRIPT=${cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld}
+ NXFLATLDSCRIPT=${cygpath -w $(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld}
else
- NXFLATLDSCRIPT=$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld
+ NXFLATLDSCRIPT=$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-gotoff.ld
endif
Then use
@@ -395,6 +395,48 @@ o Binary loaders (binfmt/)
Priority: There are too many references like the above. They will have
to get fixed as needed for Windows native tool builds.
+ Title: TOOLCHAIN COMPATIBILITY PROBLEM
+ Descripton: The older 4.3.3 compiler generates GOTOFF relocations to the constant
+ strings, like:
+
+ .L3:
+ .word .LC0(GOTOFF)
+ .word .LC1(GOTOFF)
+ .word .LC2(GOTOFF)
+ .word .LC3(GOTOFF)
+ .word .LC4(GOTOFF)
+
+ Where .LC0, LC1, LC2, LC3, and .LC4 are the labels correponding to strings in
+ the .rodata.str1.1 section. One consequence of this is that .rodata must reside
+ in D-Space since it will addressed relative to the GOT (see the section entitled
+ "Read-Only Data in RAM" at
+ http://nuttx.org/Documentation/NuttXNxFlat.html#limitations).
+
+ The newer 4.6.3compiler generated PC relative relocations to the strings:
+
+ .L2:
+ .word .LC0-(.LPIC0+4)
+ .word .LC1-(.LPIC1+4)
+ .word .LC2-(.LPIC2+4)
+ .word .LC3-(.LPIC4+4)
+ .word .LC4-(.LPIC5+4)
+
+ This is good and bad. This is good because it means that .rodata.str1.1 can not
+ reside in FLASH with .text and can be accessed using PC-relative addressing.
+ That can be accomplished by simply moving the .rodata from the .data section to
+ the .text section in the linker script. (The NXFLAT linker script is located at
+ nuttx/binfmt/libnxflat/gnu-nxflat.ld).
+
+ This is bad because a lot of stuff may get broken an a lot of test will need to
+ be done. One question that I have is does this apply to all kinds of .rodata?
+ Or just to .rodata.str1.1?
+
+ Status: Open. Many of the required changes are in place but, unfortunately, not enough
+ go be fully functional. I think all of the I-Space-to-I-Space fixes are in place.
+ However, the generated code also includes PC-relative references to .bss which
+ just cannot be done.
+ Priority: Medium. The workaround for now is to use the older, 4.3.3 OABI compiler.
+
o Network (net/, drivers/net)
^^^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h
index 1d30c5f7c..6bd842a76 100644
--- a/nuttx/arch/arm/src/armv7-m/nvic.h
+++ b/nuttx/arch/arm/src/armv7-m/nvic.h
@@ -175,7 +175,7 @@
#define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */
#define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */
#define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */
-#define NVIC_AIRC_OFFSET 0x0d0c /* Application interrupt/reset contol registr */
+#define NVIC_AIRCR_OFFSET 0x0d0c /* Application interrupt/reset contol registr */
#define NVIC_SYSCON_OFFSET 0x0d10 /* System control register */
#define NVIC_CFGCON_OFFSET 0x0d14 /* Configuration control register */
#define NVIC_SYSH_PRIORITY_OFFSET(n) (0x0d14 + 4*((n) >> 2))
@@ -348,7 +348,7 @@
#define NVIC_CPUID_BASE (ARMV7M_NVIC_BASE + NVIC_CPUID_BASE_OFFSET)
#define NVIC_INTCTRL (ARMV7M_NVIC_BASE + NVIC_INTCTRL_OFFSET)
#define NVIC_VECTAB (ARMV7M_NVIC_BASE + NVIC_VECTAB_OFFSET)
-#define NVIC_AIRC (ARMV7M_NVIC_BASE + NVIC_AIRC_OFFSET)
+#define NVIC_AIRCR (ARMV7M_NVIC_BASE + NVIC_AIRCR_OFFSET)
#define NVIC_SYSCON (ARMV7M_NVIC_BASE + NVIC_SYSCON_OFFSET)
#define NVIC_CFGCON (ARMV7M_NVIC_BASE + NVIC_CFGCON_OFFSET)
#define NVIC_SYSH_PRIORITY(n) (ARMV7M_NVIC_BASE + NVIC_SYSH_PRIORITY_OFFSET(n))
@@ -500,6 +500,20 @@
#define NVIC_SYSHCON_BUSFAULTENA (1 << 17) /* Bit 17: BusFault enabled */
#define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */
+/* Application Interrupt and Reset Control Register (AIRCR) */
+
+#define NVIC_AIRCR_VECTRESET (1 << 0) /* Bit 0: VECTRESET */
+#define NVIC_AIRCR_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */
+#define NVIC_AIRCR_SYSRESETREQ (1 << 2) /* Bit 2: System reset */
+ /* Bits 2-7: Reserved */
+#define NVIC_AIRCR_PRIGROUP_SHIFT (8) /* Bits 8-14: PRIGROUP */
+#define NVIC_AIRCR_PRIGROUP_MASK (7 << NVIC_AIRCR_PRIGROUP_SHIFT)
+#define NVIC_AIRCR_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */
+#define NVIC_AIRCR_VECTKEY_SHIFT (16) /* Bits 16-31: VECTKEY */
+#define NVIC_AIRCR_VECTKEY_MASK (0xffff << NVIC_AIRCR_VECTKEY_SHIFT)
+#define NVIC_AIRCR_VECTKEYSTAT_SHIFT (16) /* Bits 16-31: VECTKEYSTAT */
+#define NVIC_AIRCR_VECTKEYSTAT_MASK (0xffff << NVIC_AIRCR_VECTKEYSTAT_SHIFT)
+
/* Debug Exception and Monitor Control Register (DEMCR) */
#define NVIC_DEMCR_VCCORERESET (1 << 0) /* Bit 0: Reset Vector Catch */
diff --git a/nuttx/configs/px4fmu/include/drv_lis331.h b/nuttx/arch/arm/src/armv7-m/up_systemreset.c
index f4699cda0..0d7bd2736 100644
--- a/nuttx/configs/px4fmu/include/drv_lis331.h
+++ b/nuttx/arch/arm/src/armv7-m/up_systemreset.c
@@ -1,6 +1,9 @@
/****************************************************************************
+ * arch/arm/src/armv7-m/up_systemreset.c
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Darcy Gong
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -12,7 +15,7 @@
* 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
+ * 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.
*
@@ -31,53 +34,46 @@
*
****************************************************************************/
-/*
- * Driver for the ST LIS331 MEMS accelerometer
- */
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
-#include <sys/ioctl.h>
+ /****************************************************************************
+ * Public Types
+ ****************************************************************************/
-#define _LIS331BASE 0x6900
-#define LIS331C(_x) _IOC(_LIS331BASE, _x)
+/****************************************************************************
+ * Public functions
+ ****************************************************************************/
-/*
- * Sets the sensor internal sampling rate, and if a buffer
- * has been configured, the rate at which entries will be
- * added to the buffer.
- */
-#define LIS331_SETRATE LIS331C(1)
+void up_systemreset(void)
+{
+ uint32_t regval;
-#define LIS331_RATE_50Hz (0<<3)
-#define LIS331_RATE_100Hz (1<<3)
-#define LIS331_RATE_400Hz (2<<3)
-#define LIS331_RATE_1000Hz (3<<3)
+ /* Set up for the system reset, retaining the priority group from the
+ * the AIRCR register.
+ */
-/*
- * Sets the sensor internal range.
- */
-#define LIS331_SETRANGE LIS331C(2)
+ regval = getreg32(NVIC_AIRCR) & NVIC_AIRCR_PRIGROUP_MASK;
+ regval |= ((0x5fa << NVIC_AIRCR_VECTKEY_SHIFT) | NVIC_AIRCR_SYSRESETREQ);
+ putreg32(regval, NVIC_AIRCR);
-#define LIS331_RANGE_2G (0<<4)
-#define LIS331_RANGE_4G (1<<4)
-#define LIS331_RANGE_8G (3<<4)
+ /* Ensure completion of memory accesses */
-/*
- * Sets the address of a shared lis331_buffer
- * structure that is maintained by the driver.
- *
- * If zero is passed as the address, disables
- * the buffer updating.
- */
-#define LIS331_SETBUFFER LIS331C(3)
+ __asm volatile ("dsb");
-struct lis331_buffer {
- uint32_t size; /* number of entries in the samples[] array */
- uint32_t next; /* the next entry that will be populated */
- struct {
- uint16_t x;
- uint16_t y;
- uint16_t z;
- } samples[];
-};
+ /* Wait for the reset */
-extern int lis331_attach(struct spi_dev_s *spi, int spi_id);
+ for (;;);
+}
diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c
index 094835c29..80f9b1193 100644
--- a/nuttx/arch/arm/src/common/up_initialize.c
+++ b/nuttx/arch/arm/src/common/up_initialize.c
@@ -171,6 +171,12 @@ void up_initialize(void)
ramlog_consoleinit();
#endif
+ /* Initialize the Random Number Generator (RNG) */
+
+#ifdef CONFIG_DEV_RANDOM
+ up_rnginitialize();
+#endif
+
/* Initialize the system logging device */
#ifdef CONFIG_SYSLOG_CHAR
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 9f20775c0..0d3c5b1f2 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -241,6 +241,10 @@ extern void up_pminitialize(void);
# define up_pminitialize()
#endif
+#if defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4)
+extern void up_systemreset(void) noreturn_function;
+#endif
+
/* Interrupt handling *******************************************************/
extern void up_irqinitialize(void);
@@ -369,6 +373,12 @@ extern void up_usbuninitialize(void);
# define up_usbuninitialize()
#endif
+/* Random Number Generator (RNG) ********************************************/
+
+#ifdef CONFIG_DEV_RANDOM
+extern void up_rnginitialize(void);
+#endif
+
/****************************************************************************
* Name: up_check_stack
*
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 8d93fb104..2f9100236 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -269,6 +269,7 @@ config STM32_ETHMAC
bool "Ethernet MAC"
default n
depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX
+ select ARCH_HAVE_PHY
config STM32_FSMC
bool "FSMC"
@@ -319,6 +320,7 @@ config STM32_RNG
bool "RNG"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
+ select ARCH_HAVE_RNG
config STM32_SDIO
bool "SDIO"
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 32e84a78a..54067a168 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -45,8 +45,8 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
up_initialize.c up_initialstate.c up_interruptcontext.c \
up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
up_releasepending.c up_releasestack.c up_reprioritizertr.c \
- up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \
- up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
+ up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \
+ up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
up_stackcheck.c
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
@@ -83,7 +83,7 @@ endif
ifeq ($(CONFIG_USBHOST),y)
ifeq ($(CONFIG_STM32_OTGFS),y)
-CMN_CSRCS += stm32_otgfshost.c
+CMN_CSRCS += stm32_otgfshost.c
endif
endif
@@ -124,6 +124,10 @@ ifeq ($(CONFIG_DAC),y)
CHIP_CSRCS += stm32_dac.c
endif
+ifeq ($(CONFIG_DEV_RANDOM),y)
+CHIP_CSRCS += stm32_rng.c
+endif
+
ifeq ($(CONFIG_PWM),y)
CHIP_CSRCS += stm32_pwm.c
endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_rng.h b/nuttx/arch/arm/src/stm32/chip/stm32_rng.h
new file mode 100644
index 000000000..5e31d5817
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_rng.h
@@ -0,0 +1,77 @@
+/************************************************************************************
+ * arch/arm/src/stm32/chip/stm32_rng.h
+ *
+ * Copyright (C) 2012 Max Holtzberg. All rights reserved.
+ * Author: Max Holtzberg <mh@uvc.de>
+ *
+ * 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_ARM_STC_STM32_CHIP_STM32_RNG_H
+#define __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define STM32_RNG_CR_OFFSET 0x0000 /* RNG Control Register */
+#define STM32_RNG_SR_OFFSET 0x0004 /* RNG Status Register */
+#define STM32_RNG_DR_OFFSET 0x0008 /* RNG Data Register */
+
+/* Register Addresses ***************************************************************/
+
+#define STM32_RNG_CR (STM32_RNG_BASE+STM32_RNG_CR_OFFSET)
+#define STM32_RNG_SR (STM32_RNG_BASE+STM32_RNG_SR_OFFSET)
+#define STM32_RNG_DR (STM32_RNG_BASE+STM32_RNG_DR_OFFSET)
+
+/* Register Bitfield Definitions ****************************************************/
+
+/* RNG Control Register */
+
+#define RNG_CR_RNGEN (1 << 2) /* Bit 2: RNG enable */
+#define RNG_CR_IE (1 << 3) /* Bit 3: Interrupt enable */
+
+/* RNG Status Register */
+
+#define RNG_SR_DRDY (1 << 0) /* Bit 0: Data ready */
+#define RNG_SR_CECS (1 << 1) /* Bit 1: Clock error current status */
+#define RNG_SR_SECS (1 << 2) /* Bit 2: Seed error current status */
+#define RNG_SR_CEIS (1 << 5) /* Bit 5: Clock error interrupt status */
+#define RNG_SR_SEIS (1 << 6) /* Bit 6: Seed error interrupt status */
+
+#endif /* __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index 2e892c9e5..3054142ce 100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
@@ -664,6 +664,9 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv);
static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value);
static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value);
+#ifdef CONFIG_PHY_DM9161
+static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv);
+#endif
static int stm32_phyinit(FAR struct stm32_ethmac_s *priv);
/* MAC/DMA Initialization */
@@ -1653,6 +1656,7 @@ static void stm32_receive(FAR struct stm32_ethmac_s *priv)
stm32_freebuffer(priv, dev->d_buf);
dev->d_buf = NULL;
+ dev->d_len = 0;
}
}
}
@@ -1953,7 +1957,7 @@ static void stm32_polltimer(int argc, uint32_t arg, ...)
/* Check if the next TX descriptor is owned by the Ethernet DMA or CPU. We
* cannot perform the timer poll if we are unable to accept another packet
* for transmission. Hmmm.. might be bug here. Does this mean if there is
- * a transmit in progress, we will missing TCP time state updates?
+ * a transmit in progress, we will miss TCP time state updates?
*
* In a race condition, ETH_TDES0_OWN may be cleared BUT still not available
* because stm32_freeframe() has not yet run. If stm32_freeframe() has run,
@@ -2480,6 +2484,72 @@ static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t val
}
/****************************************************************************
+ * Function: stm32_dm9161
+ *
+ * Description:
+ * Special workaround for the Davicom DM9161 PHY is required. On power,
+ * up, the PHY is not usually configured correctly but will work after
+ * a powered-up reset. This is really a workaround for some more
+ * fundamental issue with the PHY clocking initialization, but the
+ * root cause has not been studied (nor will it be with this workaround).
+ *
+ * Parameters:
+ * priv - A reference to the private driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PHY_DM9161
+static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv)
+{
+ uint16_t phyval;
+ int ret;
+
+ /* Read the PHYID1 register; A failure to read the PHY ID is one
+ * indication that check if the DM9161 PHY CHIP is not ready.
+ */
+
+ ret = stm32_phyread(CONFIG_STM32_PHYADDR, MII_PHYID1, &phyval);
+ if (ret < 0)
+ {
+ ndbg("Failed to read the PHY ID1: %d\n", ret);
+ return ret;
+ }
+
+ /* If we failed to read the PHY ID1 register, the reset the MCU to recover */
+
+ else if (phyval == 0xffff)
+ {
+ up_systemreset();
+ }
+
+ nvdbg("PHY ID1: 0x%04X\n", phyval);
+
+ /* Now check the "DAVICOM Specified Configuration Register (DSCR)", Register 16 */
+
+ ret = stm32_phyread(CONFIG_STM32_PHYADDR, 16, &phyval);
+ if (ret < 0)
+ {
+ ndbg("Failed to read the PHY Register 0x10: %d\n", ret);
+ return ret;
+ }
+
+ /* Bit 8 of the DSCR register is zero, the the DM9161 has not selected RMII.
+ * If RMII is not selected, then reset the MCU to recover.
+ */
+
+ else if ((phyval & (1 << 8)) == 0)
+ {
+ up_systemreset();
+ }
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
* Function: stm32_phyinit
*
* Description:
@@ -2524,6 +2594,16 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv)
}
up_mdelay(PHY_RESET_DELAY);
+ /* Special workaround for the Davicom DM9161 PHY is required. */
+
+#ifdef CONFIG_PHY_DM9161
+ ret = stm32_dm9161(priv);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#endif
+
/* Perform auto-negotion if so configured */
#ifdef CONFIG_STM32_AUTONEG
diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.c b/nuttx/arch/arm/src/stm32/stm32_gpio.c
index 4703e8208..1dedd7ce7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_gpio.c
+++ b/nuttx/arch/arm/src/stm32/stm32_gpio.c
@@ -128,6 +128,7 @@ static inline void stm32_gpioremap(void)
val |= AFIO_MAPR_SPI1_REMAP;
#endif
#ifdef CONFIG_STM32_SPI3_REMAP
+ val |= AFIO_MAPR_SPI3_REMAP;
#endif
#ifdef CONFIG_STM32_I2C1_REMAP
diff --git a/nuttx/arch/arm/src/stm32/stm32_rng.c b/nuttx/arch/arm/src/stm32/stm32_rng.c
new file mode 100644
index 000000000..38e8108fe
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_rng.c
@@ -0,0 +1,264 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_rng.c
+ *
+ * Copyright (C) 2012 Max Holtzberg. All rights reserved.
+ * Author: Max Holtzberg <mh@uvc.de>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <stdint.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "up_arch.h"
+#include "chip/stm32_rng.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int stm32_rnginitialize(void);
+static int stm32_interrupt(int irq, void *context);
+static void stm32_enable(void);
+static void stm32_disable(void);
+static ssize_t stm32_read(struct file *filep, char *buffer, size_t);
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct rng_dev_s
+{
+ sem_t rd_devsem; /* Threads can only exclusively access the RNG */
+ sem_t rd_readsem; /* To block until the buffer is filled */
+ char *rd_buf;
+ size_t rd_buflen;
+ uint32_t rd_lastval;
+ bool rd_first;
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct rng_dev_s g_rngdev;
+
+static const struct file_operations g_rngops =
+{
+ 0, /* open */
+ 0, /* close */
+ stm32_read, /* read */
+ 0, /* write */
+ 0, /* seek */
+ 0 /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+ ,0 /* poll */
+#endif
+};
+
+/****************************************************************************
+ * Private functions
+ ****************************************************************************/
+
+static int stm32_rnginitialize()
+{
+ uint32_t regval;
+
+ vdbg("Initializing RNG\n");
+
+ memset(&g_rngdev, 0, sizeof(struct rng_dev_s));
+
+ sem_init(&g_rngdev.rd_devsem, 0, 1);
+
+ if (irq_attach(STM32_IRQ_RNG, stm32_interrupt))
+ {
+ /* We could not attach the ISR to the interrupt */
+
+ vdbg("Could not attach IRQ.\n");
+
+ return -EAGAIN;
+ }
+
+ /* Enable interrupts */
+
+ regval = getreg32(STM32_RNG_CR);
+ regval |= RNG_CR_IE;
+ putreg32(regval, STM32_RNG_CR);
+
+ up_enable_irq(STM32_IRQ_RNG);
+
+ return OK;
+}
+
+static void stm32_enable()
+{
+ uint32_t regval;
+
+ g_rngdev.rd_first = true;
+
+ regval = getreg32(STM32_RNG_CR);
+ regval |= RNG_CR_RNGEN;
+ putreg32(regval, STM32_RNG_CR);
+}
+
+static void stm32_disable()
+{
+ uint32_t regval;
+ regval = getreg32(STM32_RNG_CR);
+ regval &= ~RNG_CR_RNGEN;
+ putreg32(regval, STM32_RNG_CR);
+}
+
+static int stm32_interrupt(int irq, void *context)
+{
+ uint32_t rngsr;
+ uint32_t data;
+
+ rngsr = getreg32(STM32_RNG_SR);
+
+ if ((rngsr & (RNG_SR_SEIS | RNG_SR_CEIS)) /* Check for error bits */
+ || !(rngsr & RNG_SR_DRDY)) /* Data ready must be set */
+ {
+ /* This random value is not valid, we will try again. */
+
+ return OK;
+ }
+
+ data = getreg32(STM32_RNG_DR);
+
+ /* As required by the FIPS PUB (Federal Information Processing Standard
+ * Publication) 140-2, the first random number generated after setting the
+ * RNGEN bit should not be used, but saved for comparison with the next
+ * generated random number. Each subsequent generated random number has to be
+ * compared with the previously generated number. The test fails if any two
+ * compared numbers are equal (continuous random number generator test).
+ */
+
+ if (g_rngdev.rd_first)
+ {
+ g_rngdev.rd_first = false;
+ g_rngdev.rd_lastval = data;
+ return OK;
+ }
+
+ if (g_rngdev.rd_lastval == data)
+ {
+ /* Two subsequent same numbers, we will try again. */
+
+ return OK;
+ }
+
+ /* If we get here, the random number is valid. */
+
+ g_rngdev.rd_lastval = data;
+
+ if (g_rngdev.rd_buflen >= 4)
+ {
+ g_rngdev.rd_buflen -= 4;
+ *(uint32_t*)&g_rngdev.rd_buf[g_rngdev.rd_buflen] = data;
+ }
+ else
+ {
+ while (g_rngdev.rd_buflen > 0)
+ {
+ g_rngdev.rd_buf[--g_rngdev.rd_buflen] = (char)data;
+ data >>= 8;
+ }
+ }
+
+ if (g_rngdev.rd_buflen == 0)
+ {
+ /* Buffer filled, stop further interrupts. */
+
+ stm32_disable();
+ sem_post(&g_rngdev.rd_readsem);
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_read
+ ****************************************************************************/
+
+static ssize_t stm32_read(struct file *filep, char *buffer, size_t buflen)
+{
+ if (sem_wait(&g_rngdev.rd_devsem) != OK)
+ {
+ return -errno;
+ }
+ else
+ {
+ /* We've got the semaphore. */
+
+ /* Initialize semaphore with 0 for blocking until the buffer is filled from
+ * interrupts.
+ */
+
+ sem_init(&g_rngdev.rd_readsem, 0, 1);
+
+ g_rngdev.rd_buflen = buflen;
+ g_rngdev.rd_buf = buffer;
+
+ /* Enable RNG with interrupts */
+
+ stm32_enable();
+
+ /* Wait until the buffer is filled */
+
+ sem_wait(&g_rngdev.rd_readsem);
+
+ /* Free RNG for next use */
+
+ sem_post(&g_rngdev.rd_devsem);
+
+ return buflen;
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void up_rnginitialize()
+{
+ stm32_rnginitialize();
+ register_driver("/dev/random", &g_rngops, 0444, NULL);
+}
diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld
index e66b1dff5..47debd663 100644
--- a/nuttx/binfmt/libnxflat/gnu-nxflat.ld
+++ b/nuttx/binfmt/libnxflat/gnu-nxflat-gotoff.ld
@@ -1,7 +1,7 @@
/****************************************************************************
- * examples/nxflat/nxflat.ld
+ * examples/nxflat/gnu-nxflat-gotoff.ld
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,7 +48,17 @@ MEMORY
* (2) DSpace (Data Space). This is the segment that contains both
* read-write data (.data, .bss) as well as read-only data (.rodata).
* Everything in this segment should be access-able with machine
- * with machine load and store instructions.
+ * PIC load and store instructions.
+ *
+ * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative
+ * addressing to access RO data. In that case, read-only data (.rodata) must
+ * reside in D-Space and this linker script should be used.
+ *
+ * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative
+ * addressing to access RO data. In that case, read-only data (.rodata) must
+ * reside in I-Space and this linker script should NOT be used with those
+ * newer tools.
+ *
****************************************************************************/
SECTIONS
@@ -97,11 +107,16 @@ SECTIONS
.data 0x00000000 :
{
+ /* In this model, .rodata is access using PC-relative addressing
+ * and, hence, must also reside in the .text section.
+ */
+
__data_start = . ;
*(.rodata)
*(.rodata1)
*(.rodata.*)
*(.gnu.linkonce.r*)
+
*(.data)
*(.data1)
*(.data.*)
diff --git a/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld
new file mode 100644
index 000000000..71e4399ba
--- /dev/null
+++ b/nuttx/binfmt/libnxflat/gnu-nxflat-pcrel.ld
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * examples/nxflat/gnu-nxflat-pcrel.ld
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+ ISPACE : ORIGIN = 0x0, LENGTH = 2097152
+ DSPACE : ORIGIN = 0x0, LENGTH = 2097152
+}
+
+/****************************************************************************
+ * The XFLAT program image is divided into two segments:
+ *
+ * (1) ISpace (Instruction Space). This is the segment that contains
+ * code (.text) as well as read-only data (.rodata). Everything in the
+ * segment should be fetch-able machine PC instructions (jump, branch,
+ * call, etc.) or PC-relative loads.
+ * (2) DSpace (Data Space). This is the segment that contains read-write
+ * data (.data, .bss). Everything in this segment should be access-able
+ * with machine PIC load and store instructions.
+ *
+ * Older versions of GCC (at least up to GCC 4.3.3), use GOT-relative
+ * addressing to access RO data. In that case, read-only data (.rodata) must
+ * reside in D-Space and this linker script should NOT be used with those
+ * older tools.
+ *
+ * Newer versions of GCC (at least as of GCC 4.6.3), use PC-relative
+ * addressing to access RO data. In that case, read-only data (.rodata) must
+ * reside in I-Space and this linker script should be used.
+ *
+ ****************************************************************************/
+
+SECTIONS
+{
+ .text 0x00000000 :
+ {
+ /* ISpace is located at address 0. Every (unrelocated) ISpace
+ * address is an offset from the begining of this segment.
+ */
+
+ text_start = . ;
+
+ *(.text)
+ *(.text.*)
+ *(.gnu.warning)
+ *(.stub)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.jcr)
+
+ /* C++ support: The .init and .fini sections contain XFLAT-
+ * specific logic to manage static constructors and destructors.
+ */
+
+ *(.gnu.linkonce.t.*)
+ *(.init)
+ *(.fini)
+
+ /* This is special code area at the end of the normal
+ text section. It contains a small lookup table at
+ the start followed by the code pointed to by entries
+ in the lookup table. */
+
+ . = ALIGN (4) ;
+ PROVIDE(__ctbp = .);
+ *(.call_table_data)
+ *(.call_table_text)
+
+ /* In this model, .rodata is access using PC-relative addressing
+ * and, hence, must also reside in the .text section.
+ */
+
+ *(.rodata)
+ *(.rodata1)
+ *(.rodata.*)
+ *(.gnu.linkonce.r*)
+
+ _etext = . ;
+
+ } > ISPACE
+
+ /* DSpace is also located at address 0. Every (unrelocated) DSpace
+ * address is an offset from the begining of this segment.
+ */
+
+ .data 0x00000000 :
+ {
+ __data_start = . ;
+ *(.data)
+ *(.data1)
+ *(.data.*)
+ *(.gnu.linkonce.d*)
+ *(.data1)
+ *(.eh_frame)
+ *(.gcc_except_table)
+
+ *(.gnu.linkonce.s.*)
+ *(__libc_atexit)
+ *(__libc_subinit)
+ *(__libc_subfreeres)
+ *(.note.ABI-tag)
+
+ /* C++ support. For each global and static local C++ object,
+ * GCC creates a small subroutine to construct the object. Pointers
+ * to these routines (not the routines themselves) are stored as
+ * simple, linear arrays in the .ctors section of the object file.
+ * Similarly, pointers to global/static destructor routines are
+ * stored in .dtors.
+ */
+
+ *(.gnu.linkonce.d.*)
+
+ _ctors_start = . ;
+ *(.ctors)
+ _ctors_end = . ;
+ _dtors_start = . ;
+ *(.dtors)
+ _dtors_end = . ;
+
+ _edata = . ;
+ edata = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .bss :
+ {
+ __bss_start = _edata ;
+ *(.dynsbss)
+ *(.sbss)
+ *(.sbss.*)
+ *(.scommon)
+ *(.dynbss)
+ *(.bss)
+ *(.bss.*)
+ *(.bss*)
+ *(.gnu.linkonce.b*)
+ *(COMMON)
+ end = ALIGN( 0x10 ) ;
+ _end = ALIGN( 0x10 ) ;
+ } > DSPACE
+
+ .got 0 : { *(.got.plt) *(.got) }
+ .junk 0 : { *(.rel*) *(.rela*) }
+ /* 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) }
+}
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index b67c11ab3..ebe6d5480 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -23,6 +23,7 @@ config ARCH_BOARD_PX4IO
depends on ARCH_CHIP_STM32F100C8
---help---
PX4 system I/O expansion board
+
endchoice
config ARCH_BOARD
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 5bbec874f..e6bde645d 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -1524,7 +1524,7 @@ configs/c5471evm
This is a port to the Spectrum Digital C5471 evaluation board. The
TMS320C5471 is a dual core processor from TI with an ARM7TDMI general
purpose processor and a c54 DSP. It is also known as TMS320DA180 or just DA180.
- NuttX runs on the ARM core and is built with a GNU arm-elf toolchain*.
+ NuttX runs on the ARM core and is built with a GNU arm-nuttx-elf toolchain*.
This port is complete and verified.
configs/compal_e88 and compal_e99
@@ -1540,19 +1540,19 @@ configs/demo9s12ne64
configs/ea3131
Embedded Artists EA3131 Development board. This board is based on the
- an NXP LPC3131 MCU. This OS is built with the arm-elf toolchain*.
+ an NXP LPC3131 MCU. This OS is built with the arm-nuttx-elf toolchain*.
STATUS: This port is complete and mature.
configs/ea3152
Embedded Artists EA3152 Development board. This board is based on the
- an NXP LPC3152 MCU. This OS is built with the arm-elf toolchain*.
+ an NXP LPC3152 MCU. This OS is built with the arm-nuttx-elf toolchain*.
STATUS: This port is has not be exercised well, but since it is
a simple derivative of the ea3131, it should be fully functional.
configs/eagle100
Micromint Eagle-100 Development board. This board is based on the
an ARM Cortex-M3 MCU, the Luminary LM3S6918. This OS is built with the
- arm-elf toolchain*. STATUS: This port is complete and mature.
+ arm-nuttx-elf toolchain*. STATUS: This port is complete and mature.
configs/ekk-lm3s9b96
TI/Stellaris EKK-LM3S9B96 board. This board is based on the
@@ -1591,7 +1591,7 @@ configs/lm3s6432-s2e
configs/lm3s6965-ek
Stellaris LM3S6965 Evaluation Kit. This board is based on the
an ARM Cortex-M3 MCU, the Luminary/TI LM3S6965. This OS is built with the
- arm-elf toolchain*. STATUS: This port is complete and mature.
+ arm-nuttx-elf toolchain*. STATUS: This port is complete and mature.
configs/lm3s8962-ek
Stellaris LMS38962 Evaluation Kit.
@@ -1607,17 +1607,17 @@ configs/lpc4330-xplorer
configs/m68322evb
This is a work in progress for the venerable m68322evb board from
- Motorola. This OS is also built with the arm-elf toolchain*. STATUS:
+ Motorola. This OS is also built with the arm-nuttx-elf toolchain*. STATUS:
This port was never completed.
configs/mbed
The configurations in this directory support the mbed board (http://mbed.org)
that features the NXP LPC1768 microcontroller. This OS is also built
- with the arm-elf toolchain*. STATUS: Contributed.
+ with the arm-nuttx-elf toolchain*. STATUS: Contributed.
configs/mcu123-lpc214x
This port is for the NXP LPC2148 as provided on the mcu123.com
- lpc214x development board. This OS is also built with the arm-elf
+ lpc214x development board. This OS is also built with the arm-nuttx-elf
toolchain*. The port supports serial, timer0, spi, and usb.
configs/micropendous3
@@ -1642,7 +1642,7 @@ configs/ne64badge
not yet been fully tested.
configs/ntosd-dm320
- This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-elf
+ This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-nuttx-elf
toolchain*: see
http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home
@@ -1666,18 +1666,18 @@ configs/olimex-lpc1766stk
Linux or Cygwin. STATUS: Complete and mature.
configs/olimex-lpc2378
- This port uses the Olimex-lpc2378 board and a GNU arm-elf toolchain* under
+ This port uses the Olimex-lpc2378 board and a GNU arm-nuttx-elf toolchain* under
Linux or Cygwin. STATUS: ostest and NSH configurations available.
This port for the NXP LPC2378 was contributed by Rommel Marcelo.
configs/olimex-stm32-p107
- This port uses the Olimex STM32-P107 board (STM32F107VC) and a GNU arm-elf
+ This port uses the Olimex STM32-P107 board (STM32F107VC) and a GNU arm-nuttx-elf
toolchain* under Linux or Cygwin. See the https://www.olimex.com/dev/stm32-p107.html
for further information. Contributed by Max Holtzberg. STATUS: Configurations
for the basic OS test and NSH are available and verified.
configs/olimex-strp711
- This port uses the Olimex STR-P711 board and a GNU arm-elf toolchain* under
+ This port uses the Olimex STR-P711 board and a GNU arm-nuttx-elf toolchain* under
Linux or Cygwin. See the http://www.olimex.com/dev/str-p711.html" for
further information. STATUS: Configurations for the basic OS test and NSH
are complete and verified.
diff --git a/nuttx/configs/px4fmu/common/Make.defs b/nuttx/configs/px4fmu/common/Make.defs
index 7ba4e694a..ff2e4c5fa 100644
--- a/nuttx/configs/px4fmu/common/Make.defs
+++ b/nuttx/configs/px4fmu/common/Make.defs
@@ -55,7 +55,7 @@ NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
-MAXOPTIMIZATION = -Os
+MAXOPTIMIZATION = -O3
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
@@ -116,7 +116,6 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
-ARCHSCRIPT += -g
endif
ARCHCFLAGS = -std=gnu99
@@ -149,7 +148,7 @@ ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
-ARCHSCRIPT += --warn-common \
+EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
@@ -167,13 +166,6 @@ OBJEXT = .o
LIBEXT = .a
EXEEXT =
-# If VERBOSE is set, don't hide the compiler invocations.
-ifeq ($(VERBOSE),YES)
-_v =
-else
-_v = @
-endif
-
define PREPROCESS
@echo "CPP: $1->$2"
@$(CPP) $(CPPFLAGS) $(abspath $1) -o $2
@@ -181,17 +173,17 @@ endef
define COMPILE
@echo "CC: $1"
- $(_v)$(CC) -c $(CFLAGS) $(abspath $1) -o $2
+ $(Q)$(CC) -c $(CFLAGS) $(abspath $1) -o $2
endef
define COMPILEXX
@echo "CXX: $1"
- $(_v)$(CXX) -c $(CXXFLAGS) $(abspath $1) -o $2
+ $(Q)$(CXX) -c $(CXXFLAGS) $(abspath $1) -o $2
endef
define ASSEMBLE
@echo "AS: $1"
- $(_v)$(CC) -c $(AFLAGS) $(abspath $1) -o $2
+ $(Q)$(CC) -c $(AFLAGS) $(abspath $1) -o $2
endef
# produce partially-linked $1 from files in $2
diff --git a/nuttx/configs/px4fmu/include/drv_bma180.h b/nuttx/configs/px4fmu/include/drv_bma180.h
deleted file mode 100644
index a403415e4..000000000
--- a/nuttx/configs/px4fmu/include/drv_bma180.h
+++ /dev/null
@@ -1,99 +0,0 @@
-/*
- * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of 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.
- */
-
-/*
- * Driver for the BOSCH BMA180 MEMS accelerometer
- */
-
-/* IMPORTANT NOTES:
- *
- * SPI max. clock frequency: 25 Mhz
- * CS has to be high before transfer,
- * go low right before transfer and
- * go high again right after transfer
- *
- */
-
-#include <sys/ioctl.h>
-
-#define _BMA180BASE 0x6300
-#define BMA180C(_x) _IOC(_BMA180BASE, _x)
-
-/*
- * Sets the sensor internal sampling rate, and if a buffer
- * has been configured, the rate at which entries will be
- * added to the buffer.
- */
-#define BMA180_SETRATE BMA180C(1)
-
-#define BMA180_RATE_LP_10HZ (0<<4)
-#define BMA180_RATE_LP_20HZ (1<<4)
-#define BMA180_RATE_LP_40HZ (2<<4)
-#define BMA180_RATE_LP_75HZ (3<<4)
-#define BMA180_RATE_LP_150HZ (4<<4)
-#define BMA180_RATE_LP_300HZ (5<<4)
-#define BMA180_RATE_LP_600HZ (6<<4)
-#define BMA180_RATE_LP_1200HZ (7<<4)
-
-/*
- * Sets the sensor internal range.
- */
-#define BMA180_SETRANGE BMA180C(2)
-
-#define BMA180_RANGE_1G (0<<1)
-#define BMA180_RANGE_1_5G (1<<1)
-#define BMA180_RANGE_2G (2<<1)
-#define BMA180_RANGE_3G (3<<1)
-#define BMA180_RANGE_4G (4<<1)
-#define BMA180_RANGE_8G (5<<1)
-#define BMA180_RANGE_16G (6<<1)
-
-/*
- * Sets the address of a shared BMA180_buffer
- * structure that is maintained by the driver.
- *
- * If zero is passed as the address, disables
- * the buffer updating.
- */
-#define BMA180_SETBUFFER BMA180C(3)
-
-struct bma180_buffer {
- uint32_t size; /* number of entries in the samples[] array */
- uint32_t next; /* the next entry that will be populated */
- struct {
- uint16_t x;
- uint16_t y;
- uint16_t z;
- uint8_t temp;
- } samples[];
-};
-
-extern int bma180_attach(struct spi_dev_s *spi, int spi_id);
diff --git a/nuttx/configs/px4fmu/include/drv_hmc5883l.h b/nuttx/configs/px4fmu/include/drv_hmc5883l.h
deleted file mode 100644
index 741c3e154..000000000
--- a/nuttx/configs/px4fmu/include/drv_hmc5883l.h
+++ /dev/null
@@ -1,100 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/*
- * Driver for the ST HMC5883L gyroscope
- */
-
-#include <sys/ioctl.h>
-
-#define _HMC5883LBASE 0x6100
-#define HMC5883LC(_x) _IOC(_HMC5883LBASE, _x)
-
-/*
- * Sets the sensor internal sampling rate, and if a buffer
- * has been configured, the rate at which entries will be
- * added to the buffer.
- */
-#define HMC5883L_SETRATE HMC5883LC(1)
-
-/* set rate (configuration A register */
-#define HMC5883L_RATE_0_75HZ (0 << 2) /* 0.75 Hz */
-#define HMC5883L_RATE_1_50HZ (1 << 2) /* 1.5 Hz */
-#define HMC5883L_RATE_3_00HZ (2 << 2) /* 3 Hz */
-#define HMC5883L_RATE_7_50HZ (3 << 2) /* 7.5 Hz */
-#define HMC5883L_RATE_15HZ (4 << 2) /* 15 Hz (default) */
-#define HMC5883L_RATE_30HZ (5 << 2) /* 30 Hz */
-#define HMC5883L_RATE_75HZ (6 << 2) /* 75 Hz */
-
-/*
- * Sets the sensor internal range.
- */
-#define HMC5883L_SETRANGE HMC5883LC(2)
-
-#define HMC5883L_RANGE_0_88GA (0 << 5)
-#define HMC5883L_RANGE_1_33GA (1 << 5)
-#define HMC5883L_RANGE_1_90GA (2 << 5)
-#define HMC5883L_RANGE_2_50GA (3 << 5)
-#define HMC5883L_RANGE_4_00GA (4 << 5)
-
-/*
- * Set the sensor measurement mode.
- */
-#define HMC5883L_MODE_NORMAL (0 << 0)
-#define HMC5883L_MODE_POSITIVE_BIAS (1 << 0)
-#define HMC5883L_MODE_NEGATIVE_BIAS (1 << 1)
-
-/*
- * Sets the address of a shared HMC5883L_buffer
- * structure that is maintained by the driver.
- *
- * If zero is passed as the address, disables
- * the buffer updating.
- */
-#define HMC5883L_SETBUFFER HMC5883LC(3)
-
-struct hmc5883l_buffer {
- uint32_t size; /* number of entries in the samples[] array */
- uint32_t next; /* the next entry that will be populated */
- struct {
- int16_t x;
- int16_t y;
- int16_t z;
- } samples[];
-};
-
-#define HMC5883L_RESET HMC5883LC(4)
-#define HMC5883L_CALIBRATION_ON HMC5883LC(5)
-#define HMC5883L_CALIBRATION_OFF HMC5883LC(6)
-
-extern int hmc5883l_attach(struct i2c_dev_s *i2c);
diff --git a/nuttx/configs/px4fmu/include/drv_l3gd20.h b/nuttx/configs/px4fmu/include/drv_l3gd20.h
deleted file mode 100644
index 3b284d60d..000000000
--- a/nuttx/configs/px4fmu/include/drv_l3gd20.h
+++ /dev/null
@@ -1,108 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-/*
- * Driver for the ST L3GD20 gyroscope
- */
-
-/* IMPORTANT NOTES:
- *
- * SPI max. clock frequency: 10 Mhz
- * CS has to be high before transfer,
- * go low right before transfer and
- * go high again right after transfer
- *
- */
-
-#include <sys/ioctl.h>
-
-#define _L3GD20BASE 0x6200
-#define L3GD20C(_x) _IOC(_L3GD20BASE, _x)
-
-/*
- * Sets the sensor internal sampling rate, and if a buffer
- * has been configured, the rate at which entries will be
- * added to the buffer.
- */
-#define L3GD20_SETRATE L3GD20C(1)
-
-#define L3GD20_RATE_95HZ_LP_12_5HZ ((0<<7) | (0<<6) | (0<<5) | (0<<4))
-#define L3GD20_RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
-#define L3GD20_RATE_190HZ_LP_12_5HZ ((0<<7) | (1<<6) | (0<<5) | (0<<4))
-#define L3GD20_RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
-#define L3GD20_RATE_190HZ_LP_50HZ ((0<<7) | (1<<6) | (1<<5) | (0<<4))
-#define L3GD20_RATE_190HZ_LP_70HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
-#define L3GD20_RATE_380HZ_LP_20HZ ((1<<7) | (0<<6) | (0<<5) | (0<<4))
-#define L3GD20_RATE_380HZ_LP_25HZ ((1<<7) | (0<<6) | (0<<5) | (1<<4))
-#define L3GD20_RATE_380HZ_LP_50HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
-#define L3GD20_RATE_380HZ_LP_100HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
-#define L3GD20_RATE_760HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4))
-#define L3GD20_RATE_760HZ_LP_35HZ ((1<<7) | (1<<6) | (0<<5) | (1<<4))
-#define L3GD20_RATE_760HZ_LP_50HZ ((1<<7) | (1<<6) | (1<<5) | (0<<4))
-#define L3GD20_RATE_760HZ_LP_100HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
-
-/*
- * Sets the sensor internal range.
- */
-#define L3GD20_SETRANGE L3GD20C(2)
-
-#define L3GD20_RANGE_250DPS (0<<4)
-#define L3GD20_RANGE_500DPS (1<<4)
-#define L3GD20_RANGE_2000DPS (3<<4)
-
-#define L3GD20_RATE_95HZ ((0<<6) | (0<<4))
-#define L3GD20_RATE_190HZ ((1<<6) | (0<<4))
-#define L3GD20_RATE_380HZ ((2<<6) | (1<<4))
-#define L3GD20_RATE_760HZ ((3<<6) | (2<<4))
-
-
-
-/*
- * Sets the address of a shared l3gd20_buffer
- * structure that is maintained by the driver.
- *
- * If zero is passed as the address, disables
- * the buffer updating.
- */
-#define L3GD20_SETBUFFER L3GD20C(3)
-
-struct l3gd20_buffer {
- uint32_t size; /* number of entries in the samples[] array */
- uint32_t next; /* the next entry that will be populated */
- struct {
- int16_t x;
- int16_t y;
- int16_t z;
- } samples[];
-};
-
-extern int l3gd20_attach(struct spi_dev_s *spi, int spi_id);
diff --git a/nuttx/configs/px4fmu/include/drv_ms5611.h b/nuttx/configs/px4fmu/include/drv_ms5611.h
deleted file mode 100644
index 922a11219..000000000
--- a/nuttx/configs/px4fmu/include/drv_ms5611.h
+++ /dev/null
@@ -1,76 +0,0 @@
-/*
- * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of 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.
- */
-
-/*
- * Driver for the Meas Spec MS5611 barometric pressure sensor
- */
-
-#include <sys/ioctl.h>
-
-#define _MS5611BASE 0x6A00
-#define MS5611C(_x) _IOC(_MS5611BASE, _x)
-
-/*
- * Sets the sensor internal sampling rate, and if a buffer
- * has been configured, the rate at which entries will be
- * added to the buffer.
- */
-#define MS5611_SETRATE MS5611C(1)
-
-/* set rate (configuration A register */
-#define MS5611_RATE_0_75HZ (0 << 2) /* 0.75 Hz */
-
-/*
- * Sets the sensor internal range.
- */
-#define MS5611_SETRANGE MS5611C(2)
-
-#define MS5611_RANGE_0_88GA (0 << 5)
-
-/*
- * Sets the address of a shared MS5611_buffer
- * structure that is maintained by the driver.
- *
- * If zero is passed as the address, disables
- * the buffer updating.
- */
-#define MS5611_SETBUFFER MS5611C(3)
-
-struct ms5611_buffer {
- uint32_t size; /* number of entries in the samples[] array */
- uint32_t next; /* the next entry that will be populated */
- struct {
- uint32_t pressure;
- uint16_t temperature;
- } samples[];
-};
-
-extern int ms5611_attach(struct i2c_dev_s *i2c);
diff --git a/nuttx/configs/px4fmu/src/Makefile b/nuttx/configs/px4fmu/src/Makefile
index 5a60b7d19..48b528f6a 100644
--- a/nuttx/configs/px4fmu/src/Makefile
+++ b/nuttx/configs/px4fmu/src/Makefile
@@ -41,7 +41,7 @@ ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = up_boot.c up_leds.c up_spi.c up_hrt.c \
- drv_gpio.c drv_bma180.c drv_l3gd20.c \
+ drv_gpio.c \
drv_led.c drv_eeprom.c \
drv_tone_alarm.c up_pwm_servo.c up_usbdev.c \
up_cpuload.c
diff --git a/nuttx/configs/px4fmu/src/drv_bma180.c b/nuttx/configs/px4fmu/src/drv_bma180.c
deleted file mode 100644
index da80cc2e2..000000000
--- a/nuttx/configs/px4fmu/src/drv_bma180.c
+++ /dev/null
@@ -1,341 +0,0 @@
-/*
- * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of 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.
- */
-
-/*
- * Driver for the Bosch BMA 180 MEMS accelerometer
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/spi.h>
-#include <nuttx/arch.h>
-#include <arch/board/board.h>
-
-#include <stdio.h>
-
-#include "chip.h"
-#include "px4fmu-internal.h"
-
-#include <arch/board/drv_bma180.h>
-
-/*
- * BMA180 registers
- */
-
-/* Important Notes:
- *
- * - MAX SPI clock: 25 MHz
- * - Readout time: 0.417 ms in high accuracy mode
- * - Boot / ready time: 1.27 ms
- *
- */
-
-#define DIR_READ (1<<7)
-#define DIR_WRITE (0<<7)
-#define ADDR_INCREMENT (1<<6)
-
-#define ADDR_CHIP_ID 0x00
-#define CHIP_ID 0x03
-#define ADDR_VERSION 0x01
-
-#define ADDR_CTRL_REG0 0x0D
-#define ADDR_CTRL_REG1 0x0E
-#define ADDR_CTRL_REG2 0x0F
-#define ADDR_BWTCS 0x20
-#define ADDR_CTRL_REG3 0x21
-#define ADDR_CTRL_REG4 0x22
-#define ADDR_OLSB1 0x35
-
-#define ADDR_ACC_X_LSB 0x02
-#define ADDR_ACC_Z_MSB 0x07
-#define ADDR_TEMPERATURE 0x08
-
-#define ADDR_STATUS_REG1 0x09
-#define ADDR_STATUS_REG2 0x0A
-#define ADDR_STATUS_REG3 0x0B
-#define ADDR_STATUS_REG4 0x0C
-
-#define ADDR_RESET 0x10
-#define SOFT_RESET 0xB6
-
-#define ADDR_DIS_I2C 0x27
-
-#define REG0_WRITE_ENABLE 0x10
-
-#define RANGEMASK 0x0E
-#define BWMASK 0xF0
-
-
-static ssize_t bma180_read(struct file *filp, FAR char *buffer, size_t buflen);
-static int bma180_ioctl(struct file *filp, int cmd, unsigned long arg);
-
-static const struct file_operations bma180_fops = {
- .read = bma180_read,
- .ioctl = bma180_ioctl,
-};
-
-struct bma180_dev_s
-{
- struct spi_dev_s *spi;
- int spi_id;
- uint8_t rate;
- struct bma180_buffer *buffer;
-};
-
-static struct bma180_dev_s bma180_dev;
-
-static void bma180_write_reg(uint8_t address, uint8_t data);
-static uint8_t bma180_read_reg(uint8_t address);
-static bool read_fifo(uint16_t *data);
-static int bma180_set_range(uint8_t range);
-static int bma180_set_rate(uint8_t rate);
-
-static void
-bma180_write_reg(uint8_t address, uint8_t data)
-{
- uint8_t cmd[2] = { address | DIR_WRITE, data };
-
- SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, true);
- SPI_SNDBLOCK(bma180_dev.spi, &cmd, sizeof(cmd));
- SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, false);
-}
-
-static uint8_t
-bma180_read_reg(uint8_t address)
-{
- uint8_t cmd[2] = {address | DIR_READ, 0};
- uint8_t data[2];
-
- SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, true);
- SPI_EXCHANGE(bma180_dev.spi, cmd, data, sizeof(cmd));
- SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, false);
-
- return data[1];
-}
-
-static bool
-read_fifo(uint16_t *data)
-{
- struct { /* status register and data as read back from the device */
- uint8_t cmd;
- int16_t x;
- int16_t y;
- int16_t z;
- uint8_t temp;
- } __attribute__((packed)) report;
-
- report.cmd = ADDR_ACC_X_LSB | DIR_READ | ADDR_INCREMENT;
-
- SPI_LOCK(bma180_dev.spi, true);
- report.x = bma180_read_reg(ADDR_ACC_X_LSB);
- report.x |= (bma180_read_reg(ADDR_ACC_X_LSB+1) << 8);
- report.y = bma180_read_reg(ADDR_ACC_X_LSB+2);
- report.y |= (bma180_read_reg(ADDR_ACC_X_LSB+3) << 8);
- report.z = bma180_read_reg(ADDR_ACC_X_LSB+4);
- report.z |= (bma180_read_reg(ADDR_ACC_X_LSB+5) << 8);
- report.temp = bma180_read_reg(ADDR_ACC_X_LSB+6);
- SPI_LOCK(bma180_dev.spi, false);
-
- /* Collect status and remove two top bits */
-
- uint8_t new_data = (report.x & 0x01) + (report.x & 0x01) + (report.x & 0x01);
- report.x = (report.x >> 2);
- report.y = (report.y >> 2);
- report.z = (report.z >> 2);
-
- data[0] = report.x;
- data[1] = report.y;
- data[2] = report.z;
-
- /* return 1 for all three axes new */
- return (new_data > 0); // bit funky, depends on timing
-}
-
-static int
-bma180_set_range(uint8_t range)
-{
- /* enable writing to chip config */
- uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
- ctrl0 |= REG0_WRITE_ENABLE;
- bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
-
- /* set range */
- uint8_t olsb1 = bma180_read_reg(ADDR_OLSB1);
- olsb1 &= (~RANGEMASK);
- olsb1 |= (range);// & RANGEMASK);
- bma180_write_reg(ADDR_OLSB1, olsb1);
-
- // up_udelay(500);
-
- /* block writing to chip config */
- ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
- ctrl0 &= (~REG0_WRITE_ENABLE);
- bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
-
- uint8_t new_olsb1 = bma180_read_reg(ADDR_OLSB1);
-
- /* return 0 on success, 1 on failure */
- return !(olsb1 == new_olsb1);
-}
-
-static int
-bma180_set_rate(uint8_t rate)
-{
- /* enable writing to chip config */
- uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
- ctrl0 |= REG0_WRITE_ENABLE;
- bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
-
- /* set rate / bandwidth */
- uint8_t bwtcs = bma180_read_reg(ADDR_BWTCS);
- bwtcs &= (~BWMASK);
- bwtcs |= (rate);// & BWMASK);
- bma180_write_reg(ADDR_BWTCS, bwtcs);
-
- // up_udelay(500);
-
- /* block writing to chip config */
- ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
- ctrl0 &= (~REG0_WRITE_ENABLE);
- bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
-
- uint8_t new_bwtcs = bma180_read_reg(ADDR_BWTCS);
-
- /* return 0 on success, 1 on failure */
- return !(bwtcs == new_bwtcs);
-}
-
-static ssize_t
-bma180_read(struct file *filp, char *buffer, size_t buflen)
-{
- /* if the buffer is large enough, and data are available, return success */
- if (buflen >= 6) {
- if (read_fifo((uint16_t *)buffer))
- return 6;
-
- /* no data */
- return 0;
- }
-
- /* buffer too small */
- errno = ENOSPC;
- return ERROR;
-}
-
-static int
-bma180_ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- int result = ERROR;
-
- switch (cmd) {
- case BMA180_SETRATE:
- result = bma180_set_rate(arg);
- break;
-
- case BMA180_SETRANGE:
- result = bma180_set_range(arg);
- break;
-
- case BMA180_SETBUFFER:
- bma180_dev.buffer = (struct bma180_buffer *)arg;
- result = 0;
- break;
- }
-
- if (result)
- errno = EINVAL;
- return result;
-}
-
-int
-bma180_attach(struct spi_dev_s *spi, int spi_id)
-{
- int result = ERROR;
-
- bma180_dev.spi = spi;
- bma180_dev.spi_id = spi_id;
-
- SPI_LOCK(bma180_dev.spi, true);
-
- /* verify that the device is attached and functioning */
- if (bma180_read_reg(ADDR_CHIP_ID) == CHIP_ID) {
-
- bma180_write_reg(ADDR_RESET, SOFT_RESET); // page 48
-
- up_udelay(13000); // wait 12 ms, see page 49
-
- /* Configuring the BMA180 */
-
- /* enable writing to chip config */
- uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
- ctrl0 |= REG0_WRITE_ENABLE;
- bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
-
- /* disable I2C interface, datasheet page 31 */
- uint8_t disi2c = bma180_read_reg(ADDR_DIS_I2C);
- disi2c |= 0x01;
- bma180_write_reg(ADDR_DIS_I2C, disi2c);
-
- /* block writing to chip config */
- ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
- ctrl0 &= (~REG0_WRITE_ENABLE);
- bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
-
- // up_udelay(500);
-
- /* set rate */
- result = bma180_set_rate(BMA180_RATE_LP_600HZ);
-
- // up_udelay(500);
-
- /* set range */
- result += bma180_set_range(BMA180_RANGE_4G);
-
- // up_udelay(500);
-
- if (result == 0) {
- /* make ourselves available */
- register_driver("/dev/bma180", &bma180_fops, 0666, NULL);
- }
- } else {
- errno = EIO;
- }
-
- SPI_LOCK(bma180_dev.spi, false);
-
- return result;
-}
-
diff --git a/nuttx/configs/px4fmu/src/drv_hmc5833l.c b/nuttx/configs/px4fmu/src/drv_hmc5833l.c
deleted file mode 100644
index d51d654f7..000000000
--- a/nuttx/configs/px4fmu/src/drv_hmc5833l.c
+++ /dev/null
@@ -1,386 +0,0 @@
-/*
- * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of 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 drv_hmc5883l.c
- * Driver for the Honeywell/ST HMC5883L MEMS magnetometer
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <stdio.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/i2c.h>
-#include <arch/board/board.h>
-
-#include "chip.h"
-#include "px4fmu-internal.h"
-
-#include <arch/board/drv_hmc5883l.h>
-
-#define ADDR_CONF_A 0x00
-#define ADDR_CONF_B 0x01
-#define ADDR_MODE 0x02
-#define ADDR_DATA_OUT_X_MSB 0x03
-#define ADDR_DATA_OUT_X_LSB 0x04
-#define ADDR_DATA_OUT_Z_MSB 0x05
-#define ADDR_DATA_OUT_Z_LSB 0x06
-#define ADDR_DATA_OUT_Y_MSB 0x07
-#define ADDR_DATA_OUT_Y_LSB 0x08
-#define ADDR_STATUS 0x09
-#define ADDR_ID_A 0x10
-#define ADDR_ID_B 0x11
-#define ADDR_ID_C 0x12
-
-#define HMC5883L_ADDRESS 0x1E
-
-/* modes not changeable outside of driver */
-#define HMC5883L_MODE_NORMAL (0 << 0) /* default */
-#define HMC5883L_MODE_POSITIVE_BIAS (1 << 0) /* positive bias */
-#define HMC5883L_MODE_NEGATIVE_BIAS (1 << 1) /* negative bias */
-
-#define HMC5883L_AVERAGING_1 (0 << 5) /* conf a register */
-#define HMC5883L_AVERAGING_2 (1 << 5)
-#define HMC5883L_AVERAGING_4 (2 << 5)
-#define HMC5883L_AVERAGING_8 (3 << 5)
-
-#define MODE_REG_CONTINOUS_MODE (0 << 0)
-#define MODE_REG_SINGLE_MODE (1 << 0) /* default */
-
-#define STATUS_REG_DATA_OUT_LOCK (1 << 1) /* page 16: set if data is only partially read, read device to reset */
-#define STATUS_REG_DATA_READY (1 << 0) /* page 16: set if all axes have valid measurements */
-
-#define ID_A_WHO_AM_I 'H'
-#define ID_B_WHO_AM_I '4'
-#define ID_C_WHO_AM_I '3'
-
-static FAR struct hmc5883l_dev_s hmc5883l_dev;
-
-static ssize_t hmc5883l_read(struct file *filp, FAR char *buffer, size_t buflen);
-static int hmc5883l_ioctl(struct file *filp, int cmd, unsigned long arg);
-
-static const struct file_operations hmc5883l_fops = {
- .open = 0,
- .close = 0,
- .read = hmc5883l_read,
- .write = 0,
- .seek = 0,
- .ioctl = hmc5883l_ioctl,
-#ifndef CONFIG_DISABLE_POLL
- .poll = 0
-#endif
-};
-
-struct hmc5883l_dev_s
-{
- struct i2c_dev_s *i2c;
- uint8_t rate;
- struct hmc5883l_buffer *buffer;
-};
-static bool hmc5883l_calibration_enabled = false;
-
-static int hmc5883l_write_reg(uint8_t address, uint8_t data);
-static int hmc5883l_read_reg(uint8_t address);
-static int hmc5883l_reset(void);
-
-static int
-hmc5883l_write_reg(uint8_t address, uint8_t data)
-{
- uint8_t cmd[] = {address, data};
- return I2C_WRITE(hmc5883l_dev.i2c, cmd, 2);
-}
-
-static int
-hmc5883l_read_reg(uint8_t address)
-{
- uint8_t cmd = address;
- uint8_t data;
-
- int ret = I2C_WRITEREAD(hmc5883l_dev.i2c, &cmd, 1, &data, 1);
- /* return data on success, error code on failure */
- if (ret == OK) {
- ret = data;
- }
- return ret;
-}
-
-static int
-hmc5883l_set_range(uint8_t range)
-{
- I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
-
-
- /* mask out illegal bit positions */
- uint8_t write_range = range; //& REG4_RANGE_MASK;
- /* immediately return if user supplied invalid value */
- if (write_range != range) return EINVAL;
- /* set remaining bits to a sane value */
-// write_range |= REG4_BDU;
- /* write to device */
- hmc5883l_write_reg(ADDR_CONF_B, write_range);
- /* return 0 if register value is now written value, 1 if unchanged */
- return !(hmc5883l_read_reg(ADDR_CONF_B) == write_range);
-}
-
-static int
-hmc5883l_set_rate(uint8_t rate)
-{
- I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
- /* mask out illegal bit positions */
- uint8_t write_rate = rate;// & REG1_RATE_LP_MASK;
- /* immediately return if user supplied invalid value */
- if (write_rate != rate) return EINVAL;
- /* set remaining bits to a sane value */
-// write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
- write_rate |= HMC5883L_AVERAGING_8;
- /* write to device */
- hmc5883l_write_reg(ADDR_CONF_A, write_rate);
- /* return 0 if register value is now written value, 1 if unchanged */
- return !(hmc5883l_read_reg(ADDR_CONF_A) == write_rate);
-}
-
-static int
-hmc5883l_set_mode(uint8_t mode)
-{
- // I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
- // /* mask out illegal bit positions */
- // uint8_t write_mode = mode & 0x03;
- // /* immediately return if user supplied invalid value */
- // if (write_mode != mode) return EINVAL;
- // /* set mode */
- // write_mode |= hmc5883l_read_reg(ADDR_CONF_A);
- // /* set remaining bits to a sane value */
- // write_mode |= HMC5883L_AVERAGING_8;
- // /* write to device */
- // hmc5883l_write_reg(ADDR_CONF_A, write_mode);
- // /* return 0 if register value is now written value, 1 if unchanged */
- // return !(hmc5883l_read_reg(ADDR_CONF_A) == write_mode);
-}
-
-static bool
-read_values(int16_t *data)
-{
- struct { /* status register and data as read back from the device */
- int16_t x;
- int16_t z;
- int16_t y;
- uint8_t status;
- } __attribute__((packed)) hmc_report;
- hmc_report.status = 0;
-
- static int read_err_count = 0;
-
- /* exchange the report structure with the device */
-
- uint8_t cmd = ADDR_DATA_OUT_X_MSB;
-
- int ret = 0;
-
- I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
-
- /* set device into single mode, trigger next measurement */
- ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
-
- /* Only execute consecutive steps on success */
- if (ret == OK)
- {
- cmd = ADDR_DATA_OUT_X_MSB;
- ret = I2C_WRITEREAD(hmc5883l_dev.i2c, &cmd, 1, (uint8_t*)&hmc_report, 6);
- if (ret == OK)
- {
- /* Six bytes to read, stop if timed out */
- int hmc_status = hmc5883l_read_reg(ADDR_STATUS);
- if (hmc_status < 0)
- {
- //if (hmc_status == ETIMEDOUT)
- hmc5883l_reset();
- ret = hmc_status;
- }
- else
- {
- hmc_report.status = hmc_status;
- ret = OK;
- }
- }
- else
- {
- if (ret == ETIMEDOUT || ret == -ETIMEDOUT) hmc5883l_reset();
- }
- }
- else
- {
- if (ret == ETIMEDOUT || ret == -ETIMEDOUT) hmc5883l_reset();
- }
-
- if (ret != OK)
- {
- read_err_count++;
- /* If the last reads failed as well, reset the bus and chip */
- if (read_err_count > 3) hmc5883l_reset();
-
- *get_errno_ptr() = -ret;
- } else {
- read_err_count = 0;
- /* write values, and exchange the two 8bit blocks (big endian to little endian) */
- data[0] = ((hmc_report.x & 0x00FF) << 8) | ((hmc_report.x & 0xFF00) >> 8);
- data[1] = ((hmc_report.y & 0x00FF) << 8) | ((hmc_report.y & 0xFF00) >> 8);
- data[2] = ((hmc_report.z & 0x00FF) << 8) | ((hmc_report.z & 0xFF00) >> 8);
- // XXX TODO
- // write mode, range and lp-frequency enum values into data[3]-[6]
- if ((hmc_report.status & STATUS_REG_DATA_READY) > 0)
- {
- ret = 14;
- } else {
- ret = -EAGAIN;
- }
- }
-
- /* return len if new data is available, error else. hmc_report.status is 0 on errors */
- return ret;
-}
-
-static ssize_t
-hmc5883l_read(struct file *filp, char *buffer, size_t buflen)
-{
- /* if the buffer is large enough, and data are available, return success */
- if (buflen >= 14) {
- return read_values((int16_t *)buffer);
- }
-
- /* buffer too small */
- *get_errno_ptr() = ENOSPC;
- return -ERROR;
-}
-
-static int
-hmc5883l_ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- int result = ERROR;
-
- switch (cmd) {
- case HMC5883L_SETRATE:
- result = hmc5883l_set_rate(arg);
- break;
-
- case HMC5883L_SETRANGE:
- result = hmc5883l_set_range(arg);
- break;
-
- case HMC5883L_CALIBRATION_ON:
- hmc5883l_calibration_enabled = true;
- result = OK;
- break;
-
- case HMC5883L_CALIBRATION_OFF:
- hmc5883l_calibration_enabled = false;
- result = OK;
- break;
-//
-// case HMC5883L_SETBUFFER:
-// hmc5883l_dev.buffer = (struct hmc5883l_buffer *)arg;
-// result = 0;
-// break;
-
- case HMC5883L_RESET:
- result = hmc5883l_reset();
- break;
- }
-
- if (result)
- errno = EINVAL;
- return result;
-}
-
-extern int up_i2creset(FAR struct i2c_dev_s * dev);
-
-int hmc5883l_reset()
-{
- int ret;
-#if 1
- ret = up_i2creset(hmc5883l_dev.i2c);
- printf("HMC5883: BUS RESET %s\n", ret ? "FAIL" : "OK");
-#else
- printf("[hmc5883l drv] Resettet I2C2 BUS\n");
- up_i2cuninitialize(hmc5883l_dev.i2c);
- hmc5883l_dev.i2c = up_i2cinitialize(2);
- I2C_SETFREQUENCY(hmc5883l_dev.i2c, 400000);
-#endif
- return ret;
-}
-
-int
-hmc5883l_attach(struct i2c_dev_s *i2c)
-{
- int result = ERROR;
-
- hmc5883l_dev.i2c = i2c;
-
-// I2C_LOCK(hmc5883l_dev.i2c, true);
- I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
-
- uint8_t cmd = ADDR_STATUS;
- uint8_t status_id[4] = {0, 0, 0, 0};
-
-
- int ret = I2C_WRITEREAD(i2c, &cmd, 1, status_id, 4);
-
- /* verify that the device is attached and functioning */
- if ((ret >= 0) && (status_id[1] == ID_A_WHO_AM_I) && (status_id[2] == ID_B_WHO_AM_I) && (status_id[3] == ID_C_WHO_AM_I)) {
-
- /* set update rate to 75 Hz */
- /* set 0.88 Ga range */
- if ((ret != 0) || (hmc5883l_set_range(HMC5883L_RANGE_0_88GA) != 0) ||
- (hmc5883l_set_rate(HMC5883L_RATE_75HZ) != 0))
- {
- errno = EIO;
- } else {
-
- /* set device into single mode, start measurement */
- ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
-
- /* make ourselves available */
- register_driver("/dev/hmc5883l", &hmc5883l_fops, 0666, NULL);
-
- result = 0;
- }
-
- } else {
- errno = EIO;
- }
-
-
-
- return result;
-}
diff --git a/nuttx/configs/px4fmu/src/drv_l3gd20.c b/nuttx/configs/px4fmu/src/drv_l3gd20.c
deleted file mode 100644
index 19f2d032f..000000000
--- a/nuttx/configs/px4fmu/src/drv_l3gd20.c
+++ /dev/null
@@ -1,364 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/*
- * Driver for the ST L3GD20 MEMS gyroscope
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/spi.h>
-#include <arch/board/board.h>
-#include <nuttx/arch.h>
-#include <arch/board/drv_l3gd20.h>
-
-#include "chip.h"
-#include "stm32_internal.h"
-#include "px4fmu-internal.h"
-
-#define DIR_READ (1<<7)
-#define DIR_WRITE (0<<7)
-#define ADDR_INCREMENT (1<<6)
-
-#define ADDR_WHO_AM_I 0x0F
-#define WHO_I_AM 0xD4
-#define ADDR_CTRL_REG1 0x20
-#define ADDR_CTRL_REG2 0x21
-#define ADDR_CTRL_REG3 0x22
-#define ADDR_CTRL_REG4 0x23
-#define ADDR_CTRL_REG5 0x24
-#define ADDR_REFERENCE 0x25
-#define ADDR_OUT_TEMP 0x26
-#define ADDR_STATUS_REG 0x27
-#define ADDR_OUT_X_L 0x28
-#define ADDR_OUT_X_H 0x29
-#define ADDR_OUT_Y_L 0x2A
-#define ADDR_OUT_Y_H 0x2B
-#define ADDR_OUT_Z_L 0x2C
-#define ADDR_OUT_Z_H 0x2D
-#define ADDR_FIFO_CTRL_REG 0x2E
-#define ADDR_FIFO_SRC_REG 0x2F
-#define ADDR_INT1_CFG 0x30
-#define ADDR_INT1_SRC 0x31
-#define ADDR_INT1_TSH_XH 0x32
-#define ADDR_INT1_TSH_XL 0x33
-#define ADDR_INT1_TSH_YH 0x34
-#define ADDR_INT1_TSH_YL 0x35
-#define ADDR_INT1_TSH_ZH 0x36
-#define ADDR_INT1_TSH_ZL 0x37
-#define ADDR_INT1_DURATION 0x38
-
-#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
-#define REG4_RANGE_MASK 0x30 /* Mask to guard partial register update */
-
-/* Internal configuration values */
-#define REG1_POWER_NORMAL (1<<3)
-#define REG1_Z_ENABLE (1<<2)
-#define REG1_Y_ENABLE (1<<1)
-#define REG1_X_ENABLE (1<<0)
-
-#define REG4_BDU (1<<7)
-#define REG4_BLE (1<<6)
-//#define REG4_SPI_3WIRE (1<<0)
-
-#define REG5_FIFO_ENABLE (1<<6)
-#define REG5_REBOOT_MEMORY (1<<7)
-
-#define STATUS_ZYXOR (1<<7)
-#define STATUS_ZOR (1<<6)
-#define STATUS_YOR (1<<5)
-#define STATUS_XOR (1<<4)
-#define STATUS_ZYXDA (1<<3)
-#define STATUS_ZDA (1<<2)
-#define STATUS_YDA (1<<1)
-#define STATUS_XDA (1<<0)
-
-#define FIFO_CTRL_BYPASS_MODE (0<<5)
-#define FIFO_CTRL_FIFO_MODE (1<<5)
-#define FIFO_CTRL_STREAM_MODE (1<<6)
-#define FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
-#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
-
-static FAR struct l3gd20_dev_s l3gd20_dev;
-
-static ssize_t l3gd20_read(struct file *filp, FAR char *buffer, size_t buflen);
-static int l3gd20_ioctl(struct file *filp, int cmd, unsigned long arg);
-
-static const struct file_operations l3gd20_fops = {
- .open = 0,
- .close = 0,
- .read = l3gd20_read,
- .write = 0,
- .seek = 0,
- .ioctl = l3gd20_ioctl,
-#ifndef CONFIG_DISABLE_POLL
- .poll = 0
-#endif
-};
-
-struct l3gd20_dev_s
-{
- struct spi_dev_s *spi;
- int spi_id;
- uint8_t rate;
- struct l3gd20_buffer *buffer;
-};
-
-static void l3gd20_write_reg(uint8_t address, uint8_t data);
-static uint8_t l3gd20_read_reg(uint8_t address);
-
-static void
-l3gd20_write_reg(uint8_t address, uint8_t data)
-{
- uint8_t cmd[2] = { address | DIR_WRITE, data };
-
- SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, true);
- SPI_SNDBLOCK(l3gd20_dev.spi, &cmd, sizeof(cmd));
- SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, false);
-}
-
-static uint8_t
-l3gd20_read_reg(uint8_t address)
-{
- uint8_t cmd[2] = {address | DIR_READ, 0};
- uint8_t data[2];
-
- SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, true);
- SPI_EXCHANGE(l3gd20_dev.spi, cmd, data, sizeof(cmd));
- SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, false);
-
- return data[1];
-}
-
-static int
-set_range(uint8_t range)
-{
- /* mask out illegal bit positions */
- uint8_t write_range = range & REG4_RANGE_MASK;
- /* immediately return if user supplied invalid value */
- if (write_range != range) return EINVAL;
- /* set remaining bits to a sane value */
- write_range |= REG4_BDU;
- /* write to device */
- l3gd20_write_reg(ADDR_CTRL_REG4, write_range);
- /* return 0 if register value is now written value, 1 if unchanged */
- return !(l3gd20_read_reg(ADDR_CTRL_REG4) == write_range);
-}
-
-static int
-set_rate(uint8_t rate)
-{
- /* mask out illegal bit positions */
- uint8_t write_rate = rate & REG1_RATE_LP_MASK;
- /* immediately return if user supplied invalid value */
- if (write_rate != rate) return EINVAL;
- /* set remaining bits to a sane value */
- write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
- /* write to device */
- l3gd20_write_reg(ADDR_CTRL_REG1, write_rate);
- /* return 0 if register value is now written value, 1 if unchanged */
- return !(l3gd20_read_reg(ADDR_CTRL_REG1) == write_rate);
-}
-
-static int
-read_fifo(int16_t *data)
-{
-
- struct { /* status register and data as read back from the device */
- uint8_t cmd;
- uint8_t temp;
- uint8_t status;
- int16_t x;
- int16_t y;
- int16_t z;
- } __attribute__((packed)) report = {.status = 11};
-
- report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
-
- SPI_LOCK(l3gd20_dev.spi, true);
- SPI_SELECT(l3gd20_dev.spi, PX4_SPIDEV_GYRO, true);
- SPI_SETFREQUENCY(l3gd20_dev.spi, 25000000);
-
- SPI_EXCHANGE(l3gd20_dev.spi, &report, &report, sizeof(report));
-
- /* XXX if the status value is unchanged, attempt a second exchange */
- if (report.status == 11) SPI_EXCHANGE(l3gd20_dev.spi, &report, &report, sizeof(report));
- /* XXX set magic error value if this still didn't succeed */
- if (report.status == 11) report.status = 12;
-
- SPI_SETFREQUENCY(l3gd20_dev.spi, 10000000);
- SPI_SELECT(l3gd20_dev.spi, PX4_SPIDEV_GYRO, false);
- SPI_LOCK(l3gd20_dev.spi, false);
-
- data[0] = report.x;
- data[1] = report.y;
- data[2] = report.z;
-
- /* if all axes are valid, return buflen (6), else return negative status */
- int ret = -((int)report.status);
- if (STATUS_ZYXDA == (report.status & STATUS_ZYXDA) || STATUS_ZYXOR == (report.status & STATUS_ZYXOR))
- {
- ret = 6;
- }
-
- return ret;
-}
-
-static ssize_t
-l3gd20_read(struct file *filp, char *buffer, size_t buflen)
-{
- /* if the buffer is large enough, and data are available, return success */
- if (buflen >= 6) {
- /* return buflen or a negative value */
- int ret = read_fifo((int16_t *)buffer);
- if (ret != 6) *get_errno_ptr() = EAGAIN;
- return ret;
- }
-
- /* buffer too small */
- *get_errno_ptr() = ENOSPC;
- return ERROR;
-}
-
-static int
-l3gd20_ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- int result = ERROR;
-
- switch (cmd) {
- case L3GD20_SETRATE:
- if ((arg & REG1_RATE_LP_MASK) == arg) {
- SPI_LOCK(l3gd20_dev.spi, true);
- set_rate(arg);
- SPI_LOCK(l3gd20_dev.spi, false);
- result = 0;
- l3gd20_dev.rate = arg;
- }
- break;
-
- case L3GD20_SETRANGE:
- if ((arg & REG4_RANGE_MASK) == arg) {
- SPI_LOCK(l3gd20_dev.spi, true);
- set_range(arg);
- SPI_LOCK(l3gd20_dev.spi, false);
- result = 0;
- }
- break;
-
- case L3GD20_SETBUFFER:
- l3gd20_dev.buffer = (struct l3gd20_buffer *)arg;
- result = 0;
- break;
- }
-
- if (result)
- errno = EINVAL;
- return result;
-}
-
-int
-l3gd20_attach(struct spi_dev_s *spi, int spi_id)
-{
- int result = ERROR;
-
- l3gd20_dev.spi = spi;
- l3gd20_dev.spi_id = spi_id;
-
- SPI_LOCK(l3gd20_dev.spi, true);
- /* read dummy value to void to clear SPI statemachine on sensor */
- (void)l3gd20_read_reg(ADDR_WHO_AM_I);
-
- /* verify that the device is attached and functioning */
- if (l3gd20_read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
-
- /* reset device memory */
- //l3gd20_write_reg(ADDR_CTRL_REG5, REG5_REBOOT_MEMORY);
- //up_udelay(1000);
-
- /* set default configuration */
- l3gd20_write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
- l3gd20_write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
- l3gd20_write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
- l3gd20_write_reg(ADDR_CTRL_REG4, 0x10);
- l3gd20_write_reg(ADDR_CTRL_REG5, 0);
-
- l3gd20_write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
- l3gd20_write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */
-
- if ((set_range(L3GD20_RANGE_500DPS) != 0) ||
- (set_rate(L3GD20_RATE_760HZ_LP_100HZ) != 0)) /* takes device out of low-power mode */
- {
- errno = EIO;
- } else {
- /* Read out the first few funky values */
- struct { /* status register and data as read back from the device */
- uint8_t cmd;
- uint8_t temp;
- uint8_t status;
- int16_t x;
- int16_t y;
- int16_t z;
- } __attribute__((packed)) report;
-
- report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
-
- SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
- SPI_EXCHANGE(spi, &report, &report, sizeof(report));
- SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
- up_udelay(500);
- /* And read another set */
- SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
- SPI_EXCHANGE(spi, &report, &report, sizeof(report));
- SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
-
-
- /* make ourselves available */
- register_driver("/dev/l3gd20", &l3gd20_fops, 0666, NULL);
-
- result = 0;
- }
-
- } else {
-
- errno = EIO;
- }
-
- SPI_LOCK(l3gd20_dev.spi, false);
-
- return result;
-}
diff --git a/nuttx/configs/px4fmu/src/drv_lis331.c b/nuttx/configs/px4fmu/src/drv_lis331.c
deleted file mode 100644
index fd477b46f..000000000
--- a/nuttx/configs/px4fmu/src/drv_lis331.c
+++ /dev/null
@@ -1,272 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/*
- * Driver for the ST LIS331 MEMS accelerometer
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/spi.h>
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "chip.h"
-#include "stm32_internal.h"
-#include "px4fmu-internal.h"
-
-#include <arch/board/drv_lis331.h>
-
-/*
- * LIS331 registers
- */
-
-#define DIR_READ (1<<7)
-#define DIR_WRITE (0<<7)
-#define ADDR_INCREMENT (1<<6)
-
-#define ADDR_WHO_AM_I 0x0f
-#define WHO_I_AM 0x32
-
-#define ADDR_CTRL_REG1 0x20 /* sample rate constants are in the public header */
-#define REG1_POWER_NORMAL (1<<5)
-#define REG1_RATE_MASK (3<<3)
-#define REG1_Z_ENABLE (1<<2)
-#define REG1_Y_ENABLE (1<<1)
-#define REG1_X_ENABLE (1<<0)
-
-#define ADDR_CTRL_REG2 0x21
-
-#define ADDR_CTRL_REG3 0x22
-
-#define ADDR_CTRL_REG4 0x23
-#define REG4_BDU (1<<7)
-#define REG4_BIG_ENDIAN (1<<6)
-#define REG4_RANGE_MASK (3<<4)
-#define REG4_SPI_3WIRE (1<<0)
-
-#define ADDR_CTRL_REG5 0x24
-
-#define ADDR_HP_FILTER_RESET 0x25
-#define ADDR_REFERENCE 0x26
-#define ADDR_STATUS_REG 0x27
-#define STATUS_ZYXOR (1<<7)
-#define STATUS_ZOR (1<<6)
-#define STATUS_YOR (1<<5)
-#define STATUS_XOR (1<<4)
-#define STATUS_ZYXDA (1<<3)
-#define STATUS_ZDA (1<<2)
-#define STATUS_YDA (1<<1)
-#define STATUS_XDA (1<<0)
-
-#define ADDR_OUT_X 0x28 /* 16 bits */
-#define ADDR_OUT_Y 0x2A /* 16 bits */
-#define ADDR_OUT_Z 0x2C /* 16 bits */
-
-
-static ssize_t lis331_read(struct file *filp, FAR char *buffer, size_t buflen);
-static int lis331_ioctl(struct file *filp, int cmd, unsigned long arg);
-
-static const struct file_operations lis331_fops = {
- .read = lis331_read,
- .ioctl = lis331_ioctl,
-};
-
-struct lis331_dev_s
-{
- struct spi_dev_s *spi;
- int spi_id;
-
- uint8_t rate;
- struct lis331_buffer *buffer;
-};
-
-static struct lis331_dev_s lis331_dev;
-
-static void write_reg(uint8_t address, uint8_t data);
-static uint8_t read_reg(uint8_t address);
-static bool read_fifo(uint16_t *data);
-static void set_range(uint8_t range);
-static void set_rate(uint8_t rate);
-
-static void
-write_reg(uint8_t address, uint8_t data)
-{
- uint8_t cmd[2] = { address | DIR_WRITE, data };
-
- SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
- SPI_SNDBLOCK(lis331_dev.spi, &cmd, sizeof(cmd));
- SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
-}
-
-static uint8_t
-read_reg(uint8_t address)
-{
- uint8_t cmd[2] = {address | DIR_READ, 0};
- uint8_t data[2];
-
- SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
- SPI_EXCHANGE(lis331_dev.spi, cmd, data, sizeof(cmd));
- SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
-
- return data[1];
-}
-
-static bool
-read_fifo(uint16_t *data)
-{
- struct { /* status register and data as read back from the device */
- uint8_t cmd;
- uint8_t status;
- int16_t x;
- int16_t y;
- int16_t z;
- } __attribute__((packed)) report;
-
- report.cmd = ADDR_STATUS_REG | DIR_READ | ADDR_INCREMENT;
-
- /* exchange the report structure with the device */
- SPI_LOCK(lis331_dev.spi, true);
- SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
- SPI_EXCHANGE(lis331_dev.spi, &report, &report, sizeof(report));
- SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
- SPI_LOCK(lis331_dev.spi, false);
-
- data[0] = report.x;
- data[1] = report.y;
- data[2] = report.z;
-
- return report.status & STATUS_ZYXDA;
-}
-
-static void
-set_range(uint8_t range)
-{
- range &= REG4_RANGE_MASK;
- write_reg(ADDR_CTRL_REG4, range | REG4_BDU);
-}
-
-static void
-set_rate(uint8_t rate)
-{
- rate &= REG1_RATE_MASK;
- write_reg(ADDR_CTRL_REG1, rate | REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
-}
-
-static ssize_t
-lis331_read(struct file *filp, char *buffer, size_t buflen)
-{
- /* if the buffer is large enough, and data are available, return success */
- if (buflen >= 12) {
- if (read_fifo((uint16_t *)buffer))
- return 12;
-
- /* no data */
- return 0;
- }
-
- /* buffer too small */
- errno = ENOSPC;
- return ERROR;
-}
-
-static int
-lis331_ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- int result = ERROR;
-
- switch (cmd) {
- case LIS331_SETRATE:
- if ((arg & REG1_RATE_MASK) == arg) {
- set_rate(arg);
- result = 0;
- lis331_dev.rate = arg;
- }
- break;
-
- case LIS331_SETRANGE:
- if ((arg & REG4_RANGE_MASK) == arg) {
- set_range(arg);
- result = 0;
- }
- break;
-
- case LIS331_SETBUFFER:
- lis331_dev.buffer = (struct lis331_buffer *)arg;
- result = 0;
- break;
- }
-
- if (result)
- errno = EINVAL;
- return result;
-}
-
-int
-lis331_attach(struct spi_dev_s *spi, int spi_id)
-{
- int result = ERROR;
-
- lis331_dev.spi = spi;
-
- SPI_LOCK(lis331_dev.spi, true);
-
- /* verify that the device is attached and functioning */
- if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
-
- /* set default configuration */
- write_reg(ADDR_CTRL_REG2, 0); /* disable interrupt-generating high-pass filters */
- write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
- write_reg(ADDR_CTRL_REG5, 0); /* disable wake-on-interrupt */
-
- set_range(LIS331_RANGE_4G);
- set_rate(LIS331_RATE_400Hz); /* takes device out of low-power mode */
-
- /* make ourselves available */
- register_driver("/dev/lis331", &lis331_fops, 0666, NULL);
-
- result = 0;
- } else {
- errno = EIO;
- }
-
- SPI_LOCK(lis331_dev.spi, false);
-
- return result;
-}
-
diff --git a/nuttx/configs/px4fmu/src/drv_ms5611.c b/nuttx/configs/px4fmu/src/drv_ms5611.c
deleted file mode 100644
index c7e91c5ea..000000000
--- a/nuttx/configs/px4fmu/src/drv_ms5611.c
+++ /dev/null
@@ -1,504 +0,0 @@
-/*
- * Copyright (C) 2012 Lorenz Meier. 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 of the author or the names of 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.
- */
-
-/*
- * Driver for the Measurement Specialties MS5611 barometric pressure sensor
- */
-
-#include <nuttx/config.h>
-#include <nuttx/i2c.h>
-#include <nuttx/arch.h>
-#include <arch/board/board.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-#include <errno.h>
-#include <string.h>
-#include <stdio.h>
-#include <math.h>
-
-#include "chip.h"
-#include "px4fmu-internal.h"
-
-#include <arch/board/up_hrt.h>
-#include <arch/board/drv_ms5611.h>
-
-/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
-#define MS5611_MIN_INTER_MEASUREMENT_INTERVAL 9200
-
-#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
-#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
-
-#define ADDR_RESET_CMD 0x1E /* read from this address to reset chip (0b0011110 on bus) */
-#define ADDR_CMD_CONVERT_D1 0x48 /* 4096 samples to this address to start conversion (0b01001000 on bus) */
-#define ADDR_CMD_CONVERT_D2 0x58 /* 4096 samples */
-#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
-#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
-#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
-
-static FAR struct ms5611_dev_s ms5611_dev;
-
-static ssize_t ms5611_read(struct file *filp, FAR char *buffer, size_t buflen);
-static int ms5611_ioctl(struct file *filp, int cmd, unsigned long arg);
-
-static const struct file_operations ms5611_fops = {
- .read = ms5611_read,
- .ioctl = ms5611_ioctl,
-};
-
-struct ms5611_prom_s
-{
- uint16_t factory_setup;
- uint16_t c1_pressure_sens;
- uint16_t c2_pressure_offset;
- uint16_t c3_temp_coeff_pres_sens;
- uint16_t c4_temp_coeff_pres_offset;
- uint16_t c5_reference_temp;
- uint16_t c6_temp_coeff_temp;
- uint16_t serial_and_crc;
-} __attribute__((packed));
-
-union ms5611_prom_u
-{
- uint16_t c[8];
- struct ms5611_prom_s s;
-} __attribute__((packed));
-
-struct ms5611_dev_s
-{
- union ms5611_prom_u prom;
- struct i2c_dev_s *i2c;
- struct ms5611_buffer *buffer;
-} __attribute__((packed));
-
-static FAR uint8_t MS5611_ADDRESS;
-
-static FAR struct {
- /* status register and data as read back from the device */
- float pressure;
- float altitude;
- float temperature;
- uint32_t d1_raw;
- uint32_t d2_raw;
- uint32_t measurements_count;
- uint8_t last_state;
- uint64_t last_read;
- } ms5611_report = {
- .pressure = 0.0f,
- .altitude = 0.0f,
- .temperature = 0.0f,
- .last_state = 0,
- /* make sure the first readout can be performed */
- .last_read = 0,
-};
-
-static int ms5611_read_prom(void);
-
-int ms5611_reset()
-{
- int ret;
- printf("[ms5611 drv] Resettet I2C2 BUS\n");
- up_i2cuninitialize(ms5611_dev.i2c);
- ms5611_dev.i2c = up_i2cinitialize(2);
- I2C_SETFREQUENCY(ms5611_dev.i2c, 400000);
- return ret;
-}
-
-static bool
-read_values(float *data)
-{
- int ret;
- uint8_t cmd_data[3];
-
- /* check validity of pointer */
- if (data == NULL)
- {
- *get_errno_ptr() = EINVAL;
- return -EINVAL;
- }
-
- /* only start reading when data is available */
- if (ms5611_report.measurements_count > 0)
- {
- /* do not read more often than at minimum 9.17 ms intervals */
- if ((hrt_absolute_time() - ms5611_report.last_read) < MS5611_MIN_INTER_MEASUREMENT_INTERVAL)
- {
- /* set errno to 'come back later' */
- ret = -EAGAIN;
- goto handle_return;
- }
- else
- {
- /* set new value */
- ms5611_report.last_read = hrt_absolute_time();
- }
-
- /* Read out last measurement */
- cmd_data[0] = 0x00;
-
- struct i2c_msg_s msgv[2] = {
- {
- .addr = MS5611_ADDRESS,
- .flags = 0,
- .buffer = cmd_data,
- .length = 1
- },
- {
- .addr = MS5611_ADDRESS,
- .flags = I2C_M_READ,
- .buffer = cmd_data,
- .length = 3
- }
- };
- ret = I2C_TRANSFER(ms5611_dev.i2c, msgv, 2);
- if (ret != OK) goto handle_return;
-
-
- /* at value 1 the last reading was temperature */
- if (ms5611_report.last_state == 1)
- {
- /* put temperature into the raw set */
- ms5611_report.d2_raw = (((uint32_t)cmd_data[0]) << 16) | (((uint32_t)cmd_data[1]) << 8) | ((uint32_t)cmd_data[2]);
- }
- else
- {
- /* put altitude into the raw set */
- ms5611_report.d1_raw = (((uint32_t)cmd_data[0]) << 16) | (((uint32_t)cmd_data[1]) << 8) | ((uint32_t)cmd_data[2]);
- }
- }
- ms5611_report.measurements_count++;
-
- /*
- * this block reads four pressure values and one temp value,
- * resulting in 80 Hz pressure update and 20 Hz temperature updates
- * at 100 Hz continuous operation.
- */
- if (ms5611_report.last_state == 0)
- {
- /* request first a temperature reading */
- cmd_data[0] = ADDR_CMD_CONVERT_D2;
- }
- else
- {
- /* request pressure reading */
- cmd_data[0] = ADDR_CMD_CONVERT_D1;
- }
-
- if (ms5611_report.last_state == 3)
- {
- ms5611_report.last_state = 0;
- }
- else
- {
- ms5611_report.last_state++;
- }
-
-
- /* write measurement command */
- struct i2c_msg_s conv_cmd[1] = {
- {
- .addr = MS5611_ADDRESS,
- .flags = 0,
- .buffer = cmd_data,
- .length = 1
- },
- };
-
- ret = I2C_TRANSFER(ms5611_dev.i2c, conv_cmd, 1);
- if (ret != OK) goto handle_return;
-
- /* only write back values after first complete set */
- if (ms5611_report.measurements_count > 2)
- {
- /* Calculate results */
-
- /* temperature calculation */
- int32_t dT = ms5611_report.d2_raw - (((int32_t)ms5611_dev.prom.s.c5_reference_temp)*256);
- int64_t temp_int64 = 2000 + (((int64_t)dT)*ms5611_dev.prom.s.c6_temp_coeff_temp)/8388608;
-
- /* pressure calculation */
- int64_t offset = (int64_t)ms5611_dev.prom.s.c2_pressure_offset * 65536 + ((int64_t)dT*ms5611_dev.prom.s.c4_temp_coeff_pres_offset)/128;
- int64_t sens = (int64_t)ms5611_dev.prom.s.c1_pressure_sens * 32768 + ((int64_t)dT*ms5611_dev.prom.s.c3_temp_coeff_pres_sens)/256;
-
- /* it's pretty cold, second order temperature compensation needed */
- if (temp_int64 < 2000)
- {
- /* second order temperature compensation */
- int64_t temp2 = (((int64_t)dT)*dT) >> 31;
- int64_t tmp_64 = (temp_int64-2000)*(temp_int64-2000);
- int64_t offset2 = (5*tmp_64)>>1;
- int64_t sens2 = (5*tmp_64)>>2;
- temp_int64 = temp_int64 - temp2;
- offset = offset - offset2;
- sens = sens - sens2;
- }
-
- int64_t press_int64 = (((ms5611_report.d1_raw*sens)/2097152-offset)/32768);
-
- ms5611_report.temperature = temp_int64 / 100.0f;
- ms5611_report.pressure = press_int64 / 100.0f;
- /* convert as double for max. precision, store as float (more than enough precision) */
- ms5611_report.altitude = (44330.0 * (1.0 - pow((press_int64 / 101325.0), 0.190295)));
-
- /* Write back float values */
- data[0] = ms5611_report.pressure;
- data[1] = ms5611_report.altitude;
- data[2] = ms5611_report.temperature;
- }
- else
- {
- /* not ready, try again */
- ret = -EINPROGRESS;
- }
-
- /* return 1 if new data is available, 0 else */
- handle_return:
- if (ret == OK)
- {
- return (sizeof(ms5611_report.d1_raw) + sizeof(ms5611_report.altitude) + sizeof(ms5611_report.d2_raw));
- }
- else
- {
- errno = -ret;
- if (errno == ETIMEDOUT || ret == ETIMEDOUT) ms5611_reset();
- return ret;
- }
-}
-
-static ssize_t
-ms5611_read(struct file *filp, char *buffer, size_t buflen)
-{
- /* if the buffer is large enough, and data are available, return success */
- if (buflen >= 12) {
- return read_values((float *)buffer);
- }
-
- /* buffer too small */
- errno = ENOSPC;
- return -ENOSPC;
-}
-
-static int
-ms5611_ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- return -ENOSYS;
-
-// switch (cmd) {
-// case MS5611_SETRATE:
-// if ((arg & REG1_RATE_LP_MASK) == arg) {
-// set_rate(arg);
-// result = 0;
-// dev.rate = arg;
-// }
-// break;
-//
-// case MS5611_SETBUFFER:
-// dev.buffer = (struct ms5611_buffer *)arg;
-// result = 0;
-// break;
-// }
-//
-// if (result)
-// errno = EINVAL;
-// return result;
-}
-
-
-
-int ms5611_crc4(uint16_t n_prom[])
-{
- /* routine ported from MS5611 application note */
- int16_t cnt;
- uint16_t n_rem;
- uint16_t crc_read;
- uint8_t n_bit;
- n_rem = 0x00;
- /* save the read crc */
- crc_read = n_prom[7];
- /* remove CRC byte */
- n_prom[7] = (0xFF00 & (n_prom[7]));
- for (cnt = 0; cnt < 16; cnt++)
- {
- /* uneven bytes */
- if (cnt & 1)
- {
- n_rem ^= (uint8_t) ((n_prom[cnt>>1]) & 0x00FF);
- }
- else
- {
- n_rem ^= (uint8_t) (n_prom[cnt>>1] >> 8);
- }
- for (n_bit = 8; n_bit > 0; n_bit--)
- {
- if (n_rem & 0x8000)
- {
- n_rem = (n_rem << 1) ^ 0x3000;
-
- }
- else
- {
- n_rem = (n_rem << 1);
- }
- }
- }
- /* final 4 bit remainder is CRC value */
- n_rem = (0x000F & (n_rem >> 12));
- n_prom[7] = crc_read;
-
- /* return 0 == OK if CRCs match, 1 else */
- return !((0x000F & crc_read) == (n_rem ^ 0x00));
-}
-
-
-int ms5611_read_prom()
-{
- /* read PROM data */
- uint8_t prom_buf[2] = {255,255};
-
- int retval = 0;
-
- for (int i = 0; i < 8; i++)
- {
- uint8_t cmd = {ADDR_PROM_SETUP + (i*2)};
-
- I2C_SETADDRESS(ms5611_dev.i2c, MS5611_ADDRESS, 7);
- retval = I2C_WRITEREAD(ms5611_dev.i2c, &cmd, 1, prom_buf, 2);
-
- /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
- ms5611_dev.prom.c[i] = (((uint16_t)prom_buf[0])<<8) | ((uint16_t)prom_buf[1]);
-
- if (retval != OK)
- {
- break;
- }
- }
-
- /* calculate CRC and return error if mismatch */
- return ms5611_crc4(ms5611_dev.prom.c);
-}
-
-int
-ms5611_attach(struct i2c_dev_s *i2c)
-{
- int result = ERROR;
-
- ms5611_dev.i2c = i2c;
-
- MS5611_ADDRESS = MS5611_ADDRESS_1;
-
- /* write reset command */
- uint8_t cmd_data = ADDR_RESET_CMD;
-
- struct i2c_msg_s reset_cmd[1] = {
- {
- .addr = MS5611_ADDRESS,
- .flags = 0,
- .buffer = &cmd_data,
- .length = 1
- },
- };
-
- int ret = I2C_TRANSFER(ms5611_dev.i2c, reset_cmd, 1);
-
- if (ret == OK)
- {
- /* wait for PROM contents to be in the device (2.8 ms) */
- up_udelay(3000);
-
- /* read PROM */
- ret = ms5611_read_prom();
- }
-
- /* check if the address was wrong */
- if (ret != OK)
- {
- /* try second address */
- MS5611_ADDRESS = MS5611_ADDRESS_2;
-
- /* write reset command */
- cmd_data = ADDR_RESET_CMD;
-
- struct i2c_msg_s reset_cmd_2[1] = {
- {
- .addr = MS5611_ADDRESS,
- .flags = 0,
- .buffer = &cmd_data,
- .length = 1
- },
- };
-
- ret = I2C_TRANSFER(ms5611_dev.i2c, reset_cmd_2, 1);
-
- /* wait for PROM contents to be in the device (2.8 ms) */
- up_udelay(3000);
-
- /* read PROM */
- ret = ms5611_read_prom();
- }
-
- if (ret < 0) return -EIO;
-
-
- /* verify that the device is attached and functioning */
- if (ret == OK) {
-
- if (MS5611_ADDRESS == MS5611_ADDRESS_1)
- {
- printf("[ms5611 driver] Attached MS5611 at addr #1 (0x76)\n");
- }
- else
- {
- printf("[ms5611 driver] Attached MS5611 at addr #2 (0x77)\n");
- }
-
- /* trigger temperature read */
- (void)read_values(NULL);
- /* wait for conversion to complete */
- up_udelay(9200);
-
- /* trigger pressure read */
- (void)read_values(NULL);
- /* wait for conversion to complete */
- up_udelay(9200);
- /* now a read_values call would obtain valid results */
-
- /* make ourselves available */
- register_driver("/dev/ms5611", &ms5611_fops, 0666, NULL);
-
- result = OK;
-
- } else {
- errno = EIO;
- }
-
- return result;
-}
diff --git a/nuttx/configs/px4fmu/src/up_nsh.c b/nuttx/configs/px4fmu/src/up_nsh.c
index 25f3c2795..af8253181 100644
--- a/nuttx/configs/px4fmu/src/up_nsh.c
+++ b/nuttx/configs/px4fmu/src/up_nsh.c
@@ -61,8 +61,6 @@
#include <arch/board/drv_tone_alarm.h>
#include <arch/board/up_adc.h>
#include <arch/board/board.h>
-#include <arch/board/drv_bma180.h>
-#include <arch/board/drv_l3gd20.h>
#include <arch/board/drv_led.h>
#include <arch/board/drv_eeprom.h>
@@ -181,7 +179,7 @@ int nsh_archinitialize(void)
return -ENODEV;
}
- // Setup 10 MHz clock (maximum rate the BMA180 can sustain)
+ // Default SPI1 to 1MHz and de-assert the known chip selects.
SPI_SETFREQUENCY(spi1, 10000000);
SPI_SETBITS(spi1, 8);
SPI_SETMODE(spi1, SPIDEV_MODE3);
@@ -192,33 +190,6 @@ int nsh_archinitialize(void)
message("[boot] Successfully initialized SPI port 1\r\n");
- /* initialize SPI peripherals redundantly */
- int gyro_attempts = 0;
- int gyro_fail = 0;
-
- while (gyro_attempts < 5)
- {
- gyro_fail = l3gd20_attach(spi1, PX4_SPIDEV_GYRO);
- gyro_attempts++;
- if (gyro_fail == 0) break;
- up_udelay(1000);
- }
-
- if (!gyro_fail) message("[boot] Found L3GD20 gyro\n");
-
- int acc_attempts = 0;
- int acc_fail = 0;
-
- while (acc_attempts < 5)
- {
- acc_fail = bma180_attach(spi1, PX4_SPIDEV_ACCEL);
- acc_attempts++;
- if (acc_fail == 0) break;
- up_udelay(1000);
- }
-
- if (!acc_fail) message("[boot] Found BMA180 accelerometer\n");
-
/* initialize I2C2 bus */
i2c2 = up_i2cinitialize(2);
diff --git a/nuttx/configs/px4io/common/setenv.sh b/nuttx/configs/px4io/common/setenv.sh
index ee33a8d21..ff9a4bf8a 100755
--- a/nuttx/configs/px4io/common/setenv.sh
+++ b/nuttx/configs/px4io/common/setenv.sh
@@ -41,7 +41,7 @@ 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}/../buildroot/build_arm_nofpu/staging_dir/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}"
diff --git a/nuttx/configs/px4io/io/setenv.sh b/nuttx/configs/px4io/io/setenv.sh
index ee33a8d21..ff9a4bf8a 100755
--- a/nuttx/configs/px4io/io/setenv.sh
+++ b/nuttx/configs/px4io/io/setenv.sh
@@ -41,7 +41,7 @@ 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}/../buildroot/build_arm_nofpu/staging_dir/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}"
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index ea218a592..1d263ec14 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -11,6 +11,14 @@ config DEV_ZERO
bool "Enable /dev/zero"
default n
+config ARCH_HAVE_RNG
+ bool
+
+config DEV_RANDOM
+ bool "Enable /dev/random"
+ default n
+ depends on ARCH_HAVE_RNG
+
config LOOP
bool "Enable loop device"
default n
diff --git a/nuttx/drivers/input/Kconfig b/nuttx/drivers/input/Kconfig
index 9fde35ff6..1f345ee14 100644
--- a/nuttx/drivers/input/Kconfig
+++ b/nuttx/drivers/input/Kconfig
@@ -2,6 +2,7 @@
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
+
config INPUT_TSC2007
bool "TI TSC2007 touchscreen controller"
default n
@@ -9,7 +10,29 @@ config INPUT_TSC2007
---help---
Enable support for the TI TSC2007 touchscreen controller
-
+if INPUT_TSC2007
+
+config TSC2007_8BIT
+ bool "8-bit Conversions"
+ default n
+ ---help---
+ Use faster, but less accurate, 8-bit conversions. Default: 12-bit conversions.
+
+config TSC2007_MULTIPLE
+ bool "Multiple TSC2007 Devices"
+ default n
+ ---help---
+ Can be defined to support multiple TSC2007 devices on board.
+
+config TSC2007_NPOLLWAITERS
+ int "Number poll waiters"
+ default 4
+ depends on !DISABLE_POLL
+ ---help---
+ Maximum number of threads that can be waiting on poll()
+
+endif
+
config INPUT_ADS7843E
bool "TI ADS7843/TSC2046 touchscreen controller"
default n
@@ -18,3 +41,169 @@ config INPUT_ADS7843E
Enable support for the TI/Burr-Brown ADS7842 touchscreen controller. I believe
that driver should be compatibile with the TI/Burr-Brown TSC2046 and XPT2046
touchscreen controllers as well.
+
+if INPUT_ADS7843E
+
+config ADS7843E_MULTIPLE
+ bool "Multiple ADS7843E Devices"
+ default n
+ ---help---
+ Can be defined to support multiple ADS7843E devices on board.
+
+config ADS7843E_NPOLLWAITERS
+ int "Number poll waiters"
+ default 4
+ depends on !DISABLE_POLL
+ ---help---
+ Maximum number of threads that can be waiting on poll()
+
+config ADS7843E_SPIMODE
+ int "SPI mode"
+ default 0
+ range 0,3
+ ---help---
+ Controls the SPI mode. The device should work in mode 0, but sometimes
+ you need to experiment.
+
+config ADS7843E_FREQUENCY
+ int "SPI frequency"
+ default 100000
+ ---help---
+ Define to use a different SPI bus frequency.
+
+config ADS7843E_SWAPXY
+ bool "Swap X/Y"
+ default n
+ ---help---
+ Reverse the meaning of X and Y to handle different LCD orientations.
+
+config ADS7843E_THRESHX
+ int "X threshold"
+ default 12
+ ---help---
+ New touch positions will only be reported when the X or Y data changes by these
+ thresholds. This trades reduces data rate for some loss in dragging accuracy. For
+ 12-bit values so the raw ranges are 0-4095. So for example, if your display is
+ 320x240, then THRESHX=13 and THRESHY=17 would correspond to one pixel. Default: 12
+
+config ADS7843E_THRESHY
+ int "Y threshold"
+ default 12
+ ---help---
+ New touch positions will only be reported when the X or Y data changes by these
+ thresholds. This trades reduces data rate for some loss in dragging accuracy. For
+ 12-bit values so the raw ranges are 0-4095. So for example, if your display is
+ 320x240, then THRESHX=13 and THRESHY=17 would correspond to one pixel. Default: 12
+
+endif
+
+config INPUT_STMPE811
+ bool "STMicro STMPE811 Driver"
+ default n
+ ---help---
+ Enables support for the STMPE811 driver
+
+if INPUT_STMPE811
+
+choice
+ prompt "STMPE Interface"
+ default STMPE811_I2C
+
+config STMPE811_SPI
+ bool "SPI Interface"
+ select SPI
+ ---help---
+ Enables support for the SPI interface (not currently supported)
+
+config STMPE811_I2C
+ bool "STMPE811 I2C Interface"
+ select I2C
+ ---help---
+ Enables support for the I2C interface
+
+endchoice
+
+config STMPE811_MULTIPLE
+ bool "Multiple STMPE811 Devices"
+ default n
+ ---help---
+ Can be defined to support multiple STMPE811 devices on board.
+
+config STMPE811_NPOLLWAITERS
+ int "Number poll waiters"
+ default 4
+ depends on !DISABLE_POLL
+ ---help---
+ Maximum number of threads that can be waiting on poll()
+
+config STMPE811_TSC_DISABLE
+ bool "Disable STMPE811 Touchscreen Support"
+ default n
+ ---help---
+ Disable driver touchscreen functionality.
+
+config STMPE811_SWAPXY
+ bool "Swap X/Y"
+ default n
+ depends on !STMPE811_TSC_DISABLE
+ ---help---
+ Reverse the meaning of X and Y to handle different LCD orientations.
+
+config STMPE811_THRESHX
+ int "X threshold"
+ default 12
+ depends on !STMPE811_TSC_DISABLE
+ ---help---
+ STMPE811 touchscreen data comes in a a very high rate. New touch positions
+ will only be reported when the X or Y data changes by these thresholds.
+ This trades reduces data rate for some loss in dragging accuracy. The
+ STMPE811 is configure for 12-bit values so the raw ranges are 0-4095. So
+ for example, if your display is 320x240, then THRESHX=13 and THRESHY=17
+ would correspond to one pixel. Default: 12
+
+config STMPE811_THRESHY
+ int "Y threshold"
+ default 12
+ depends on !STMPE811_TSC_DISABLE
+ ---help---
+ STMPE811 touchscreen data comes in a a very high rate. New touch positions
+ will only be reported when the X or Y data changes by these thresholds.
+ This trades reduces data rate for some loss in dragging accuracy. The
+ STMPE811 is configure for 12-bit values so the raw ranges are 0-4095. So
+ for example, if your display is 320x240, then THRESHX=13 and THRESHY=17
+ would correspond to one pixel. Default: 12
+
+config STMPE811_ADC_DISABLE
+ bool "Disable STMPE811 ADC Support"
+ default y
+ ---help---
+ Disable driver ADC functionality.
+
+config STMPE811_GPIO_DISABLE
+ bool "Disable STMPE811 GPIO Support"
+ default y
+ ---help---
+ Disable driver GPIO functionality.
+
+config STMPE811_GPIOINT_DISABLE
+ bool "Disable STMPE811 GPIO Interrupt Support"
+ default y
+ depends on !STMPE811_GPIO_DISABLE
+ ---help---
+ Disable driver GPIO interrupt functionlality (ignored if GPIO functionality is
+ disabled).
+
+config STMPE811_TEMP_DISABLE
+ bool "Disable STMPE811 Temperature Sensor Support"
+ default y
+ ---help---
+ Disable driver temperature sensor functionality.
+
+config STMPE811_REGDEBUG
+ bool "Enable Register-Level STMPE811 Debug"
+ default n
+ depends on DEBUG
+ ---help---
+ Enable very low register-level debug output.
+
+endif
diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c
index 07e5e515d..06969e6d2 100644
--- a/nuttx/drivers/input/ads7843e.c
+++ b/nuttx/drivers/input/ads7843e.c
@@ -79,6 +79,12 @@
* Pre-processor Definitions
****************************************************************************/
+/* This is a value for the threshold that guantees a big difference on the
+ * first pendown (but can't overflow).
+ */
+
+#define INVALID_THRESHOLD 0x1000
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -88,13 +94,14 @@
****************************************************************************/
/* Low-level SPI helpers */
-static inline void ads7843e_configspi(FAR struct spi_dev_s *spi);
#ifdef CONFIG_SPI_OWNBUS
-static inline void ads7843e_select(FAR struct spi_dev_s *spi);
-static inline void ads7843e_deselect(FAR struct spi_dev_s *spi);
+static inline void ads7843e_configspi(FAR struct spi_dev_s *spi);
+# define ads7843e_lock(spi)
+# define ads7843e_unlock(spi)
#else
-static void ads7843e_select(FAR struct spi_dev_s *spi);
-static void ads7843e_deselect(FAR struct spi_dev_s *spi);
+# define ads7843e_configspi(spi);
+static void ads7843e_lock(FAR struct spi_dev_s *spi);
+static void ads7843e_unlock(FAR struct spi_dev_s *spi);
#endif
static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv);
@@ -157,13 +164,12 @@ static struct ads7843e_dev_s *g_ads7843elist;
****************************************************************************/
/****************************************************************************
- * Function: ads7843e_select
+ * Function: ads7843e_lock
*
* Description:
- * Select the SPI, locking and re-configuring if necessary. This function
- * must be called before initiating any sequence of SPI operations. If we
- * are sharing the SPI bus with other devices (CONFIG_SPI_OWNBUS undefined)
- * then we need to lock and configure the SPI bus for each transfer.
+ * Lock the SPI bus and re-configure as necessary. This function must be
+ * to assure: (1) exclusive access to the SPI bus, and (2) to assure that
+ * the shared bus is properly configured for the touchscreen controller.
*
* Parameters:
* spi - Reference to the SPI driver structure
@@ -175,42 +181,35 @@ static struct ads7843e_dev_s *g_ads7843elist;
*
****************************************************************************/
-#ifdef CONFIG_SPI_OWNBUS
-static inline void ads7843e_select(FAR struct spi_dev_s *spi)
-{
- /* We own the SPI bus, so just select the chip */
-
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
-}
-#else
-static void ads7843e_select(FAR struct spi_dev_s *spi)
+#ifndef CONFIG_SPI_OWNBUS
+static void ads7843e_lock(FAR struct spi_dev_s *spi)
{
- /* Select ADS7843 chip (locking the SPI bus in case there are multiple
- * devices competing for the SPI bus
+ /* Lock the SPI bus because there are multiple devices competing for the
+ * SPI bus
*/
(void)SPI_LOCK(spi, true);
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
- /* Now make sure that the SPI bus is configured for the ADS7843 (it
- * might have gotten configured for a different device while unlocked)
+ /* We have the lock. Now make sure that the SPI bus is configured for the
+ * ADS7843 (it might have gotten configured for a different device while
+ * unlocked)
*/
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE);
SPI_SETBITS(spi, 8);
SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY);
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
}
#endif
/****************************************************************************
- * Function: ads7843e_deselect
+ * Function: ads7843e_unlock
*
* Description:
- * De-select the SPI, unlocking as necessary. This function must be
- * after completing a sequence of SPI operations. If we are sharing the SPI
- * bus with other devices (CONFIG_SPI_OWNBUS undefined) then we need to
- * un-lock the SPI bus for each transfer, possibly losing the current
- * configuration.
+ * If we are sharing the SPI bus with other devices (CONFIG_SPI_OWNBUS
+ * undefined) then we need to un-lock the SPI bus for each transfer,
+ * possibly losing the current configuration.
*
* Parameters:
* spi - Reference to the SPI driver structure
@@ -222,19 +221,11 @@ static void ads7843e_select(FAR struct spi_dev_s *spi)
*
****************************************************************************/
-#ifdef CONFIG_SPI_OWNBUS
-static inline void ads7843e_deselect(FAR struct spi_dev_s *spi)
-{
- /* We own the SPI bus, so just de-select the chip */
-
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
-}
-#else
-static void ads7843e_deselect(FAR struct spi_dev_s *spi)
+#ifndef CONFIG_SPI_OWNBUS
+static void ads7843e_unlock(FAR struct spi_dev_s *spi)
{
- /* De-select ADS7843 chip and relinquish the SPI bus. */
+ /* Relinquish the SPI bus. */
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
(void)SPI_LOCK(spi, false);
}
#endif
@@ -258,23 +249,20 @@ static void ads7843e_deselect(FAR struct spi_dev_s *spi)
*
****************************************************************************/
+#ifdef CONFIG_SPI_OWNBUS
static inline void ads7843e_configspi(FAR struct spi_dev_s *spi)
{
- idbg("Mode: %d Bits: 8 Frequency: %d\n",
- CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY);
-
/* Configure SPI for the ADS7843. But only if we own the SPI bus. Otherwise, don't
* bother because it might change.
*/
-#ifdef CONFIG_SPI_OWNBUS
SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE);
SPI_SETBITS(spi, 8);
SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY);
SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
-#endif
}
+#endif
/****************************************************************************
* Name: ads7843e_waitbusy
@@ -296,7 +284,7 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd)
/* Select the ADS7843E */
- ads7843e_select(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, true);
/* Send the command */
@@ -306,7 +294,7 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd)
/* Read the data */
SPI_RECVBLOCK(priv->spi, buffer, 2);
- ads7843e_deselect(priv->spi);
+ SPI_SELECT(priv->spi, SPIDEV_TOUCHSCREEN, false);
result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1];
result = result >> 4;
@@ -554,7 +542,12 @@ static void ads7843e_worker(FAR void *arg)
{
FAR struct ads7843e_dev_s *priv = (FAR struct ads7843e_dev_s *)arg;
FAR struct ads7843e_config_s *config;
+ uint16_t x;
+ uint16_t y;
+ uint16_t xdiff;
+ uint16_t ydiff;
bool pendown;
+ int ret;
ASSERT(priv != NULL);
@@ -565,10 +558,30 @@ static void ads7843e_worker(FAR void *arg)
config = priv->config;
DEBUGASSERT(config != NULL);
- /* Disable the watchdog timer */
+ /* Disable the watchdog timer. This is safe because it is started only
+ * by this function and this function is serialized on the worker thread.
+ */
wd_cancel(priv->wdog);
+ /* Lock the SPI bus so that we have exclusive access */
+
+ ads7843e_lock(priv->spi);
+
+ /* Get exclusive access to the driver data structure */
+
+ do
+ {
+ ret = sem_wait(&priv->devsem);
+
+ /* This should only fail if the wait was canceled by an signal
+ * (and the worker thread will receive a lot of signals).
+ */
+
+ DEBUGASSERT(ret == OK || errno == EINTR);
+ }
+ while (ret < 0);
+
/* Check for pen up or down by reading the PENIRQ GPIO. */
pendown = config->pendown(config);
@@ -577,13 +590,20 @@ static void ads7843e_worker(FAR void *arg)
if (!pendown)
{
- /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up and
- * already reported. CONTACT_UP == pen up, but not reported)
+ /* The pen is up.. reset thresholding variables. */
+
+ priv->threshx = INVALID_THRESHOLD;
+ priv->threshy = INVALID_THRESHOLD;
+
+ /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up
+ * and already reported; CONTACT_UP == pen up, but not reported)
*/
- if (priv->sample.contact == CONTACT_NONE)
+ if (priv->sample.contact == CONTACT_NONE ||
+ priv->sample.contact == CONTACT_UP)
+
{
- goto errout;
+ goto ignored;
}
/* The pen is up. NOTE: We know from a previous test, that this is a
@@ -601,14 +621,57 @@ static void ads7843e_worker(FAR void *arg)
else if (priv->sample.contact == CONTACT_UP)
{
- goto errout;
+ /* If we have not yet processed the last pen up event, then we
+ * cannot handle this pen down event. We will have to discard it. That
+ * should be okay because we will set the timer to to sample again
+ * later.
+ */
+
+ wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv);
+ goto ignored;
}
else
{
/* Handle pen down events. First, sample positional values. */
- priv->sample.x = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION);
- priv->sample.y = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION);
+#ifdef CONFIG_ADS7843E_SWAPXY
+ x = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION);
+ y = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION);
+#else
+ x = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION);
+ y = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION);
+#endif
+
+ /* Perform a thresholding operation so that the results will be more stable.
+ * If the difference from the last sample is small, then ignore the event.
+ * REVISIT: Should a large change in pressure also generate a event?
+ */
+
+ xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x);
+ ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y);
+
+ /* Continue to sample the position while the pen is down */
+
+ wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv);
+
+ /* Check the thresholds. Bail if there is no significant difference */
+
+ if (xdiff < CONFIG_ADS7843E_THRESHX && ydiff < CONFIG_ADS7843E_THRESHY)
+ {
+ /* Little or no change in either direction ... don't report anything. */
+
+ goto ignored;
+ }
+
+ /* When we see a big difference, snap to the new x/y thresholds */
+
+ priv->threshx = x;
+ priv->threshy = y;
+
+ /* Update the x/y position in the sample data */
+
+ priv->sample.x = priv->threshx;
+ priv->sample.y = priv->threshy;
/* The X/Y positional data is now valid */
@@ -625,10 +688,6 @@ static void ads7843e_worker(FAR void *arg)
priv->sample.contact = CONTACT_DOWN;
}
-
- /* Continue to sample the position while the pen is down */
-
- wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv);
}
/* Indicate the availability of new sample data for this ID */
@@ -642,9 +701,15 @@ static void ads7843e_worker(FAR void *arg)
/* Exit, re-enabling ADS7843E interrupts */
-errout:
+ignored:
+
(void)ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ);
config->enable(config, true);
+
+ /* Release our lock on the state structure and unlock the SPI bus */
+
+ sem_post(&priv->devsem);
+ ads7843e_unlock(priv->spi);
}
/****************************************************************************
@@ -871,7 +936,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
report = (FAR struct touch_sample_s *)buffer;
memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1));
report->npoints = 1;
- report->point[0].id = priv->id;
+ report->point[0].id = sample.id;
report->point[0].x = sample.x;
report->point[0].y = sample.y;
@@ -886,8 +951,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
if (sample.valid)
{
- report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID |
- TOUCH_POS_VALID | TOUCH_PRESSURE_VALID;
+ report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID;
}
else
{
@@ -1098,7 +1162,7 @@ errout:
*
****************************************************************************/
-int ads7843e_register(FAR struct spi_dev_s *dev,
+int ads7843e_register(FAR struct spi_dev_s *spi,
FAR struct ads7843e_config_s *config, int minor)
{
FAR struct ads7843e_dev_s *priv;
@@ -1108,11 +1172,11 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
#endif
int ret;
- ivdbg("dev: %p minor: %d\n", dev, minor);
+ ivdbg("spi: %p minor: %d\n", spi, minor);
/* Debug-only sanity checks */
- DEBUGASSERT(dev != NULL && config != NULL && minor >= 0 && minor < 100);
+ DEBUGASSERT(spi != NULL && config != NULL && minor >= 0 && minor < 100);
/* Create and initialize a ADS7843E device driver instance */
@@ -1130,11 +1194,14 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
/* Initialize the ADS7843E device driver instance */
memset(priv, 0, sizeof(struct ads7843e_dev_s));
- priv->spi = dev; /* Save the SPI device handle */
- priv->config = config; /* Save the board configuration */
- priv->wdog = wd_create(); /* Create a watchdog timer */
- sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */
- sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */
+ priv->spi = spi; /* Save the SPI device handle */
+ priv->config = config; /* Save the board configuration */
+ priv->wdog = wd_create(); /* Create a watchdog timer */
+ priv->threshx = INVALID_THRESHOLD; /* Initialize thresholding logic */
+ priv->threshy = INVALID_THRESHOLD; /* Initialize thresholding logic */
+
+ sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */
+ sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */
/* Make sure that interrupts are disabled */
@@ -1150,14 +1217,25 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
goto errout_with_priv;
}
+ idbg("Mode: %d Bits: 8 Frequency: %d\n",
+ CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY);
+
+ /* Lock the SPI bus so that we have exclusive access */
+
+ ads7843e_lock(spi);
+
/* Configure the SPI interface */
- ads7843e_configspi(dev);
+ ads7843e_configspi(spi);
/* Enable the PEN IRQ */
ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ);
+ /* Unlock the bus */
+
+ ads7843e_unlock(spi);
+
/* Register the device as an input device */
(void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
diff --git a/nuttx/drivers/input/ads7843e.h b/nuttx/drivers/input/ads7843e.h
index 43b79c7b7..6fd70d98b 100644
--- a/nuttx/drivers/input/ads7843e.h
+++ b/nuttx/drivers/input/ads7843e.h
@@ -139,6 +139,8 @@ struct ads7843e_dev_s
uint8_t nwaiters; /* Number of threads waiting for ADS7843E data */
uint8_t id; /* Current touch point ID */
volatile bool penchange; /* An unreported event is buffered */
+ uint16_t threshx; /* Thresholding X value */
+ uint16_t threshy; /* Thresholding Y value */
sem_t devsem; /* Manages exclusive access to this structure */
sem_t waitsem; /* Used to wait for the availability of data */
diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c
index 3d5ba96d3..e42b5bded 100644
--- a/nuttx/drivers/lcd/ssd1289.c
+++ b/nuttx/drivers/lcd/ssd1289.c
@@ -229,8 +229,8 @@
/* Debug ******************************************************************************/
#ifdef CONFIG_DEBUG_LCD
-# define lcddbg dbg
-# define lcdvdbg vdbg
+# define lcddbg dbg
+# define lcdvdbg vdbg
#else
# define lcddbg(x...)
# define lcdvdbg(x...)
@@ -253,6 +253,16 @@ struct ssd1289_dev_s
FAR struct ssd1289_lcd_s *lcd; /* The contained platform-specific, LCD interface */
uint8_t power; /* Current power setting */
+ /* These fields simplify and reduce debug output */
+
+#ifdef CONFIG_DEBUG_LCD
+ bool put; /* Last raster operation was a putrun */
+ fb_coord_t firstrow; /* First row of the run */
+ fb_coord_t lastrow; /* Last row of the run */
+ fb_coord_t col; /* Column of the run */
+ size_t npixels; /* Length of the run */
+#endif
+
/* This is working memory allocated by the LCD driver for each LCD device
* and for each color plane. This memory will hold one raster line of data.
* The size of the allocated run buffer must therefore be at least
@@ -287,6 +297,19 @@ static void ssd1289_setcursor(FAR struct ssd1289_lcd_s *lcd, uint16_t column,
/* LCD Data Transfer Methods */
+#if 0 /* Sometimes useful */
+static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixels);
+#else
+# define ssd1289_dumprun(m,r,n)
+#endif
+
+#ifdef CONFIG_DEBUG_LCD
+static void ssd1289_showrun(FAR struct ssd1289_dev_s *priv, fb_coord_t row,
+ fb_coord_t col, size_t npixels, bool put);
+#else
+# define ssd1289_showrun(p,r,c,n,b)
+#endif
+
static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
size_t npixels);
static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
@@ -489,6 +512,64 @@ static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixe
#endif
/**************************************************************************************
+ * Name: ssd1289_showrun
+ *
+ * Description:
+ * When LCD debug is enabled, try to reduce then amount of ouptut data generated by
+ * ssd1289_putrun and ssd1289_getrun
+ *
+ **************************************************************************************/
+
+#ifdef CONFIG_DEBUG_LCD
+static void ssd1289_showrun(FAR struct ssd1289_dev_s *priv, fb_coord_t row,
+ fb_coord_t col, size_t npixels, bool put)
+{
+ fb_coord_t nextrow = priv->lastrow + 1;
+
+ /* Has anything changed (other than the row is the next row in the sequence)? */
+
+ if (put == priv->put && row == nextrow && col == priv->col &&
+ npixels == priv->npixels)
+ {
+ /* No, just update the last row */
+
+ priv->lastrow = nextrow;
+ }
+ else
+ {
+ /* Yes... then this is the end of the preceding sequence. Output the last run
+ * (if there were more than one run in the sequence).
+ */
+
+ if (priv->firstrow != priv->lastrow)
+ {
+ lcddbg("...\n");
+ lcddbg("%s row: %d col: %d npixels: %d\n",
+ priv->put ? "PUT" : "GET",
+ priv->lastrow, priv->col, priv->npixels);
+ }
+
+ /* And we are starting a new sequence. Output the first run of the
+ * new sequence
+ */
+
+ lcddbg("%s row: %d col: %d npixels: %d\n",
+ put ? "PUT" : "GET", row, col, npixels);
+
+ /* And save information about the run so that we can detect continuations
+ * of the sequence.
+ */
+
+ priv->put = put;
+ priv->firstrow = row;
+ priv->lastrow = row;
+ priv->col = col;
+ priv->npixels = npixels;
+ }
+}
+#endif
+
+/**************************************************************************************
* Name: ssd1289_putrun
*
* Description:
@@ -512,7 +593,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf
/* Buffer must be provided and aligned to a 16-bit address boundary */
- lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels);
+ ssd1289_showrun(priv, row, col, npixels, true);
DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
/* Select the LCD */
@@ -536,7 +617,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf
ssd1289_gramselect(lcd);
ssd1289_gramwrite(lcd, *src);
- /* Increment to next column */
+ /* Increment to the next column */
src++;
col++;
@@ -581,7 +662,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf
ssd1289_gramselect(lcd);
ssd1289_gramwrite(lcd, *src);
- /* Increment to next column */
+ /* Increment to the next column */
src++;
col--;
@@ -604,7 +685,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf
ssd1289_gramselect(lcd);
ssd1289_gramwrite(lcd, *src);
- /* Decrement to next column */
+ /* Decrement to the next column */
src++;
col++;
@@ -632,7 +713,7 @@ static int ssd1289_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buf
**************************************************************************************/
static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
- size_t npixels)
+ size_t npixels)
{
#ifndef CONFIG_LCD_NOGETRUN
FAR struct ssd1289_dev_s *priv = &g_lcddev;
@@ -643,7 +724,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
/* Buffer must be provided and aligned to a 16-bit address boundary */
- lcdvdbg("row: %d col: %d npixels: %d\n", row, col, npixels);
+ ssd1289_showrun(priv, row, col, npixels, false);
DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
/* Select the LCD */
@@ -666,7 +747,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
ssd1289_readsetup(lcd, &accum);
*dest++ = ssd1289_gramread(lcd, &accum);
- /* Increment to next column */
+ /* Increment to the next column */
col++;
}
@@ -715,7 +796,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
ssd1289_readsetup(lcd, &accum);
*dest++ = ssd1289_gramread(lcd, &accum);
- /* Increment to next column */
+ /* Increment to the next column */
col--;
}
@@ -738,7 +819,7 @@ static int ssd1289_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
ssd1289_readsetup(lcd, &accum);
*dest++ = ssd1289_gramread(lcd, &accum);
- /* Decrement to next column */
+ /* Decrement to the next column */
col++;
}
@@ -931,9 +1012,27 @@ static inline int ssd1289_hwinitialize(FAR struct ssd1289_dev_s *priv)
lcd->select(lcd);
+ /* Read the device ID. Skip verification of the device ID is the LCD is
+ * write-only. What choice do we have?
+ */
+
#ifndef CONFIG_LCD_NOGETRUN
id = ssd1289_readreg(lcd, SSD1289_DEVCODE);
- lcddbg("LCD ID: %04x\n", id);
+ if (id != 0)
+ {
+ lcddbg("LCD ID: %04x\n", id);
+ }
+
+ /* If we could not get the ID, then let's just assume that this is an SSD1289.
+ * Perhaps we have some early register access issues. This seems to happen.
+ * But then perhaps we should not even bother to read the device ID at all?
+ */
+
+ else
+ {
+ lcddbg("No LCD ID, assuming SSD1289\n");
+ id = SSD1289_DEVCODE_VALUE;
+ }
/* Check if the ID is for the SSD1289 */
diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c
index 074545e2d..34273bccf 100644
--- a/nuttx/drivers/mtd/ramtron.c
+++ b/nuttx/drivers/mtd/ramtron.c
@@ -98,7 +98,7 @@
#define RAMTRON_WRITE 0x02 /* 1 Write A 0 1-256 */
#define RAMTRON_SLEEP 0xb9 // TODO:
#define RAMTRON_RDID 0x9f /* 1 Read Identification 0 0 1-3 */
-#define RAMTRON_SN 0xc3 // TODO:
+#define RAMTRON_SN 0xc3 // TODO:
/* Status register bit definitions */
@@ -125,12 +125,12 @@
struct ramtron_parts_s
{
- const char *name;
- uint8_t id1;
- uint8_t id2;
- uint32_t size;
- uint8_t addr_len;
- uint32_t speed;
+ const char *name;
+ uint8_t id1;
+ uint8_t id2;
+ uint32_t size;
+ uint8_t addr_len;
+ uint32_t speed;
};
/* This type represents the state of the MTD device. The struct mtd_dev_s
@@ -146,84 +146,86 @@ struct ramtron_dev_s
uint8_t pageshift;
uint16_t nsectors;
uint32_t npages;
- const struct ramtron_parts_s *part; /* part instance */
+ const struct ramtron_parts_s *part; /* part instance */
};
/************************************************************************************
* Supported Part Lists
************************************************************************************/
-// Defines the initial speed compatible with all devices. In case of RAMTRON
-// the defined devices within the part list have all the same speed.
-#define RAMTRON_INIT_CLK_MAX 40000000UL
+/* Defines the initial speed compatible with all devices. In case of RAMTRON
+ * the defined devices within the part list have all the same speed.
+ */
+
+#define RAMTRON_INIT_CLK_MAX 40000000UL
static struct ramtron_parts_s ramtron_parts[] =
{
- {
- "FM25V02", /* name */
- 0x22, /* id1 */
- 0x00, /* id2 */
- 32L*1024L, /* size */
- 2, /* addr_len */
- 40000000 /* speed */
- },
- {
- "FM25VN02", /* name */
- 0x22, /* id1 */
- 0x01, /* id2 */
- 32L*1024L, /* size */
- 2, /* addr_len */
- 40000000 /* speed */
- },
- {
- "FM25V05", /* name */
- 0x23, /* id1 */
- 0x00, /* id2 */
- 64L*1024L, /* size */
- 2, /* addr_len */
- 40000000 /* speed */
- },
- {
- "FM25VN05", /* name */
- 0x23, /* id1 */
- 0x01, /* id2 */
- 64L*1024L, /* size */
- 2, /* addr_len */
- 40000000 /* speed */
- },
- {
- "FM25V10", /* name */
- 0x24, /* id1 */
- 0x00, /* id2 */
- 128L*1024L, /* size */
- 3, /* addr_len */
- 40000000 /* speed */
- },
- {
- "FM25VN10", /* name */
- 0x24, /* id1 */
- 0x01, /* id2 */
- 128L*1024L, /* size */
- 3, /* addr_len */
- 40000000 /* speed */
- },
+ {
+ "FM25V02", /* name */
+ 0x22, /* id1 */
+ 0x00, /* id2 */
+ 32L*1024L, /* size */
+ 2, /* addr_len */
+ 40000000 /* speed */
+ },
+ {
+ "FM25VN02", /* name */
+ 0x22, /* id1 */
+ 0x01, /* id2 */
+ 32L*1024L, /* size */
+ 2, /* addr_len */
+ 40000000 /* speed */
+ },
+ {
+ "FM25V05", /* name */
+ 0x23, /* id1 */
+ 0x00, /* id2 */
+ 64L*1024L, /* size */
+ 2, /* addr_len */
+ 40000000 /* speed */
+ },
+ {
+ "FM25VN05", /* name */
+ 0x23, /* id1 */
+ 0x01, /* id2 */
+ 64L*1024L, /* size */
+ 2, /* addr_len */
+ 40000000 /* speed */
+ },
+ {
+ "FM25V10", /* name */
+ 0x24, /* id1 */
+ 0x00, /* id2 */
+ 128L*1024L, /* size */
+ 3, /* addr_len */
+ 40000000 /* speed */
+ },
+ {
+ "FM25VN10", /* name */
+ 0x24, /* id1 */
+ 0x01, /* id2 */
+ 128L*1024L, /* size */
+ 3, /* addr_len */
+ 40000000 /* speed */
+ },
#ifdef CONFIG_RAMTRON_FRAM_NON_JEDEC
- {
- "FM25H20", /* name */
- 0xff, /* id1 */
- 0xff, /* id2 */
- 256L*1024L, /* size */
- 3, /* addr_len */
- 40000000 /* speed */
- },
- {
- NULL, /* name */
- 0, /* id1 */
- 0, /* id2 */
- 0, /* size */
- 0, /* addr_len */
- 0 /* speed */
- }
+ {
+ "FM25H20", /* name */
+ 0xff, /* id1 */
+ 0xff, /* id2 */
+ 256L*1024L, /* size */
+ 3, /* addr_len */
+ 40000000 /* speed */
+ },
+ {
+ NULL, /* name */
+ 0, /* id1 */
+ 0, /* id2 */
+ 0, /* size */
+ 0, /* addr_len */
+ 0 /* speed */
+ }
#endif
};
@@ -240,17 +242,17 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv);
static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv);
static void ramtron_writeenable(struct ramtron_dev_s *priv);
static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer,
- off_t offset);
+ off_t offset);
/* MTD driver methods */
static int ramtron_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock,
- size_t nblocks, FAR uint8_t *buf);
+ size_t nblocks, FAR uint8_t *buf);
static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
- size_t nblocks, FAR const uint8_t *buf);
+ size_t nblocks, FAR const uint8_t *buf);
static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
- FAR uint8_t *buffer);
+ FAR uint8_t *buffer);
static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
/************************************************************************************
@@ -317,31 +319,37 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv)
/* Send the "Read ID (RDID)" command and read the first three ID bytes */
(void)SPI_SEND(priv->dev, RAMTRON_RDID);
- for (i=0; i<6; i++) manufacturer = SPI_SEND(priv->dev, RAMTRON_DUMMY);
- memory = SPI_SEND(priv->dev, RAMTRON_DUMMY);
- capacity = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id1
- part = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id2
+ for (i = 0; i < 6; i++)
+ {
+ manufacturer = SPI_SEND(priv->dev, RAMTRON_DUMMY);
+ }
+
+ memory = SPI_SEND(priv->dev, RAMTRON_DUMMY);
+ capacity = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id1
+ part = SPI_SEND(priv->dev, RAMTRON_DUMMY); // fram.id2
/* Deselect the FLASH and unlock the bus */
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
ramtron_unlock(priv->dev);
- // Select part from the part list
+ /* Select part from the part list */
+
for (priv->part = ramtron_parts;
- priv->part->name != NULL && !(priv->part->id1 == capacity && priv->part->id2 == part);
- priv->part++);
-
- if (priv->part->name) {
- fvdbg("RAMTRON %s of size %d bytes (mf:%02x mem:%02x cap:%02x part:%02x)\n",
- priv->part->name, priv->part->size, manufacturer, memory, capacity, part);
-
- priv->sectorshift = RAMTRON_EMULATE_SECTOR_SHIFT;
- priv->nsectors = priv->part->size / (1 << RAMTRON_EMULATE_SECTOR_SHIFT);
- priv->pageshift = RAMTRON_EMULATE_PAGE_SHIFT;
- priv->npages = priv->part->size / (1 << RAMTRON_EMULATE_PAGE_SHIFT);
- return OK;
- }
+ priv->part->name != NULL && !(priv->part->id1 == capacity && priv->part->id2 == part);
+ priv->part++);
+
+ if (priv->part->name)
+ {
+ fvdbg("RAMTRON %s of size %d bytes (mf:%02x mem:%02x cap:%02x part:%02x)\n",
+ priv->part->name, priv->part->size, manufacturer, memory, capacity, part);
+
+ priv->sectorshift = RAMTRON_EMULATE_SECTOR_SHIFT;
+ priv->nsectors = priv->part->size / (1 << RAMTRON_EMULATE_SECTOR_SHIFT);
+ priv->pageshift = RAMTRON_EMULATE_PAGE_SHIFT;
+ priv->npages = priv->part->size / (1 << RAMTRON_EMULATE_PAGE_SHIFT);
+ return OK;
+ }
fvdbg("RAMTRON device not found\n");
return -ENODEV;
@@ -408,8 +416,10 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a
DEBUGASSERT(priv->part->addr_len == 3 || priv->part->addr_len == 2);
if (priv->part->addr_len == 3)
- (void)SPI_SEND(priv->dev, (addr >> 16) & 0xff);
-
+ {
+ (void)SPI_SEND(priv->dev, (addr >> 16) & 0xff);
+ }
+
(void)SPI_SEND(priv->dev, (addr >> 8) & 0xff);
(void)SPI_SEND(priv->dev, addr & 0xff);
}
@@ -419,7 +429,7 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a
************************************************************************************/
static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer,
- off_t page)
+ off_t page)
{
off_t offset = page << priv->pageshift;
@@ -475,7 +485,7 @@ static int ramtron_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nbl
************************************************************************************/
static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
- FAR uint8_t *buffer)
+ FAR uint8_t *buffer)
{
FAR struct ramtron_dev_s *priv = (FAR struct ramtron_dev_s *)dev;
ssize_t nbytes;
@@ -489,6 +499,7 @@ static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t
{
return nbytes >> priv->pageshift;
}
+
return (int)nbytes;
}
@@ -497,7 +508,7 @@ static ssize_t ramtron_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t
************************************************************************************/
static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
- FAR const uint8_t *buffer)
+ FAR const uint8_t *buffer)
{
FAR struct ramtron_dev_s *priv = (FAR struct ramtron_dev_s *)dev;
size_t blocksleft = nblocks;
@@ -512,8 +523,8 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_
ramtron_pagewrite(priv, buffer, startblock);
startblock++;
}
- ramtron_unlock(priv->dev);
+ ramtron_unlock(priv->dev);
return nblocks;
}
@@ -522,7 +533,7 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_
************************************************************************************/
static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes,
- FAR uint8_t *buffer)
+ FAR uint8_t *buffer)
{
FAR struct ramtron_dev_s *priv = (FAR struct ramtron_dev_s *)dev;
@@ -662,6 +673,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev)
if (ramtron_readid(priv) != OK)
{
/* Unrecognized! Discard all of that work we just did and return NULL */
+
kfree(priv);
priv = NULL;
}
diff --git a/nuttx/drivers/mtd/w25.c b/nuttx/drivers/mtd/w25.c
index 0d7028fec..bd6680fdf 100644
--- a/nuttx/drivers/mtd/w25.c
+++ b/nuttx/drivers/mtd/w25.c
@@ -693,7 +693,7 @@ static void w25_pagewrite(struct w25_dev_s *priv, FAR const uint8_t *buffer,
uint8_t status;
fvdbg("address: %08lx nwords: %d\n", (long)address, (int)nbytes);
- DEBUGASSERT(priv && buffer && ((uintptr_t)buffer & 0xff) == 0 &&
+ DEBUGASSERT(priv && buffer && (address & 0xff) == 0 &&
(nbytes & 0xff) == 0);
for (; nbytes > 0; nbytes -= W25_PAGE_SIZE)
@@ -955,36 +955,27 @@ static int w25_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks
static ssize_t w25_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
FAR uint8_t *buffer)
{
-#ifdef CONFIG_W25_SECTOR512
ssize_t nbytes;
fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
/* On this device, we can handle the block read just like the byte-oriented read */
+#ifdef CONFIG_W25_SECTOR512
nbytes = w25_read(dev, startblock << W25_SECTOR512_SHIFT, nblocks << W25_SECTOR512_SHIFT, buffer);
if (nbytes > 0)
{
- return nbytes >> W25_SECTOR512_SHIFT;
+ nbytes >>= W25_SECTOR512_SHIFT;
}
-
- return (int)nbytes;
#else
- FAR struct w25_dev_s *priv = (FAR struct w25_dev_s *)dev;
- ssize_t nbytes;
-
- fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
-
- /* On this device, we can handle the block read just like the byte-oriented read */
-
nbytes = w25_read(dev, startblock << W25_SECTOR_SHIFT, nblocks << W25_SECTOR_SHIFT, buffer);
if (nbytes > 0)
{
- return nbytes >> W25_SECTOR_SHIFT;
+ nbytes >>= W25_SECTOR_SHIFT;
}
-
- return (int)nbytes;
#endif
+
+ return nbytes;
}
/************************************************************************************
diff --git a/nuttx/fs/nxffs/Kconfig b/nuttx/fs/nxffs/Kconfig
index b233e85ea..9f4ef8231 100644
--- a/nuttx/fs/nxffs/Kconfig
+++ b/nuttx/fs/nxffs/Kconfig
@@ -12,31 +12,31 @@ config FS_NXFFS
if FS_NXFFS
config NXFFS_ERASEDSTATE
- bool "FLASH erased state"
- default n
+ hex "FLASH erased state"
+ default 0xff
---help---
The erased state of FLASH.
This must have one of the values of 0xff or 0x00.
Default: 0xff.
config NXFFS_PACKTHRESHOLD
- bool "Re-packing threshold"
- default n
+ int "Re-packing threshold"
+ default 32
---help---
When packing flash file data,
don't both with file chunks smaller than this number of data bytes.
Default: 32.
config NXFFS_MAXNAMLEN
- bool "Maximum file name length"
- default n
+ int "Maximum file name length"
+ default 255
---help---
The maximum size of an NXFFS file name.
Default: 255.
config NXFFS_TAILTHRESHOLD
- bool "Tail threshold"
- default n
+ int "Tail threshold"
+ default 8192
---help---
clean-up can either mean
packing files together toward the end of the file or, if file are
diff --git a/nuttx/include/nuttx/input/ads7843e.h b/nuttx/include/nuttx/input/ads7843e.h
index 53aa2f227..fe4382f2f 100644
--- a/nuttx/include/nuttx/input/ads7843e.h
+++ b/nuttx/include/nuttx/input/ads7843e.h
@@ -70,6 +70,16 @@
# define CONFIG_ADS7843E_SPIMODE SPIDEV_MODE0
#endif
+/* Thresholds */
+
+#ifndef CONFIG_ADS7843E_THRESHX
+# define CONFIG_ADS7843E_THRESHX 12
+#endif
+
+#ifndef CONFIG_ADS7843E_THRESHY
+# define CONFIG_ADS7843E_THRESHY 12
+#endif
+
/* Check for some required settings. This can save the user a lot of time
* in getting the right configuration.
*/
@@ -149,7 +159,7 @@ extern "C" {
* number
*
* Input Parameters:
- * dev - An SPI driver instance
+ * spi - An SPI driver instance
* config - Persistent board configuration data
* minor - The input device minor number
*
@@ -159,7 +169,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN int ads7843e_register(FAR struct spi_dev_s *dev,
+EXTERN int ads7843e_register(FAR struct spi_dev_s *spi,
FAR struct ads7843e_config_s *config,
int minor);
diff --git a/nuttx/include/nuttx/input/stmpe811.h b/nuttx/include/nuttx/input/stmpe811.h
index cea54a34f..fc311f7c4 100644
--- a/nuttx/include/nuttx/input/stmpe811.h
+++ b/nuttx/include/nuttx/input/stmpe811.h
@@ -85,7 +85,7 @@
* CONFIG_STMPE811_TEMP_DISABLE
* Disable driver temperature sensor functionality.
* CONFIG_STMPE811_REGDEBUG
- * Enabled very low register-level debug output. Requires CONFIG_DEBUG.
+ * Enable very low register-level debug output. Requires CONFIG_DEBUG.
* CONFIG_STMPE811_THRESHX and CONFIG_STMPE811_THRESHY
* STMPE811 touchscreen data comes in a a very high rate. New touch positions
* will only be reported when the X or Y data changes by these thresholds.
diff --git a/nuttx/lib/stdio/lib_libvsprintf.c b/nuttx/lib/stdio/lib_libvsprintf.c
index 2bf095880..30c988599 100644
--- a/nuttx/lib/stdio/lib_libvsprintf.c
+++ b/nuttx/lib/stdio/lib_libvsprintf.c
@@ -1169,7 +1169,9 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a
FAR char *ptmp;
#ifndef CONFIG_NOPRINTF_FIELDWIDTH
int width;
+#ifdef CONFIG_LIBC_FLOATINGPOINT
int trunc;
+#endif
uint8_t fmt;
#endif
uint8_t flags;
@@ -1212,8 +1214,10 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a
#ifndef CONFIG_NOPRINTF_FIELDWIDTH
fmt = FMT_RJUST;
width = 0;
+#ifdef CONFIG_LIBC_FLOATINGPOINT
trunc = 0;
#endif
+#endif
/* Process each format qualifier. */
@@ -1260,8 +1264,10 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a
int value = va_arg(ap, int);
if (IS_HASDOT(flags))
{
+#ifdef CONFIG_LIBC_FLOATINGPOINT
trunc = value;
SET_HASASTERISKTRUNC(flags);
+#endif
}
else
{
@@ -1300,7 +1306,9 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a
if (IS_HASDOT(flags))
{
+#ifdef CONFIG_LIBC_FLOATINGPOINT
trunc = n;
+#endif
}
else
{
diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig
index 718b28b8f..d4ea8befb 100644
--- a/nuttx/net/Kconfig
+++ b/nuttx/net/Kconfig
@@ -18,6 +18,9 @@ choice
prompt "Board PHY Selection"
depends on ARCH_HAVE_PHY
default PHY_KS8721
+ ---help---
+ Identify the PHY on your board. This setting is not used by all Ethernet
+ drivers no do all Ethernet drivers support all PHYs.
config PHY_KS8721
bool "Micrel KS8721 PHY"
@@ -28,6 +31,9 @@ config PHY_DP83848C
config PHY_LAN8720
bool "SMSC LAN8720 PHY"
+config PHY_DM9161
+ bool "Davicom DM9161 PHY"
+
endchoice
config NET_NOINTS
diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c
index 356187d09..e3ebf7252 100644
--- a/nuttx/net/uip/uip_icmpping.c
+++ b/nuttx/net/uip/uip_icmpping.c
@@ -148,122 +148,129 @@ static inline int ping_timeout(struct icmp_ping_s *pstate)
****************************************************************************/
static uint16_t ping_interrupt(struct uip_driver_s *dev, void *conn,
- void *pvpriv, uint16_t flags)
+ void *pvpriv, uint16_t flags)
{
struct icmp_ping_s *pstate = (struct icmp_ping_s *)pvpriv;
uint8_t *ptr;
- int failcode = -ETIMEDOUT;
int i;
nllvdbg("flags: %04x\n", flags);
if (pstate)
{
- /* Check if this device is on the same network as the destination device. */
-
- if (!uip_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
- {
- /* Destination address was not on the local network served by this
- * device. If a timeout occurs, then the most likely reason is
- * that the destination address is not reachable.
- */
+ /* Check if this is a ICMP ECHO reply. If so, return the sequence
+ * number to the caller. NOTE: We may not even have sent the
+ * requested ECHO request; this could have been the delayed ECHO
+ * response from a previous ping.
+ */
- nllvdbg("Not reachable\n");
- failcode = -ENETUNREACH;
- }
- else
+ if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL)
{
- /* Check if this is a ICMP ECHO reply. If so, return the sequence
- * number to the caller. NOTE: We may not even have sent the
- * requested ECHO request; this could have been the delayed ECHO
- * response from a previous ping.
- */
+ struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn;
+ nlldbg("ECHO reply: id=%d seqno=%d\n",
+ ntohs(icmp->id), ntohs(icmp->seqno));
- if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL)
+ if (ntohs(icmp->id) == pstate->png_id)
{
- struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn;
- nlldbg("ECHO reply: id=%d seqno=%d\n", ntohs(icmp->id), ntohs(icmp->seqno));
+ /* Consume the ECHOREPLY */
- if (ntohs(icmp->id) == pstate->png_id)
- {
- /* Consume the ECHOREPLY */
+ flags &= ~UIP_ECHOREPLY;
+ dev->d_len = 0;
- flags &= ~UIP_ECHOREPLY;
- dev->d_len = 0;
+ /* Return the result to the caller */
- /* Return the result to the caller */
-
- pstate->png_result = OK;
- pstate->png_seqno = ntohs(icmp->seqno);
- goto end_wait;
- }
+ pstate->png_result = OK;
+ pstate->png_seqno = ntohs(icmp->seqno);
+ goto end_wait;
}
+ }
- /* Check:
- * If the outgoing packet is available (it may have been claimed
- * by a sendto interrupt serving a different thread
- * -OR-
- * If the output buffer currently contains unprocessed incoming
- * data.
- * -OR-
- * If we have alread sent the ECHO request
- *
- * In the first two cases, we will just have to wait for the next
- * polling cycle.
- */
+ /* Check:
+ * If the outgoing packet is available (it may have been claimed
+ * by a sendto interrupt serving a different thread)
+ * -OR-
+ * If the output buffer currently contains unprocessed incoming
+ * data.
+ * -OR-
+ * If we have alread sent the ECHO request
+ *
+ * In the first two cases, we will just have to wait for the next
+ * polling cycle.
+ */
- if (dev->d_sndlen <= 0 && /* Packet available */
- (flags & UIP_NEWDATA) == 0 && /* No incoming data */
- !pstate->png_sent) /* Request not sent */
- {
- struct uip_icmpip_hdr *picmp = ICMPBUF;
+ if (dev->d_sndlen <= 0 && /* Packet available */
+ (flags & UIP_NEWDATA) == 0 && /* No incoming data */
+ !pstate->png_sent) /* Request not sent */
+ {
+ struct uip_icmpip_hdr *picmp = ICMPBUF;
- /* We can send the ECHO request now.
- *
- * Format the ICMP ECHO request packet
- */
+ /* We can send the ECHO request now.
+ *
+ * Format the ICMP ECHO request packet
+ */
- picmp->type = ICMP_ECHO_REQUEST;
- picmp->icode = 0;
+ picmp->type = ICMP_ECHO_REQUEST;
+ picmp->icode = 0;
#ifndef CONFIG_NET_IPv6
- picmp->id = htons(pstate->png_id);
- picmp->seqno = htons(pstate->png_seqno);
+ picmp->id = htons(pstate->png_id);
+ picmp->seqno = htons(pstate->png_seqno);
#else
# error "IPv6 ECHO Request not implemented"
#endif
- /* Add some easily verifiable data */
+ /* Add some easily verifiable data */
- for (i = 0, ptr = ICMPDAT; i < pstate->png_datlen; i++)
- {
- *ptr++ = i;
- }
+ for (i = 0, ptr = ICMPDAT; i < pstate->png_datlen; i++)
+ {
+ *ptr++ = i;
+ }
- /* Send the ICMP echo request. Note that d_sndlen is set to
- * the size of the ICMP payload and does not include the size
- * of the ICMP header.
- */
+ /* Send the ICMP echo request. Note that d_sndlen is set to
+ * the size of the ICMP payload and does not include the size
+ * of the ICMP header.
+ */
- nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno);
+ nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno);
- dev->d_sndlen = pstate->png_datlen + 4;
- uip_icmpsend(dev, &pstate->png_addr);
- pstate->png_sent = true;
- return flags;
- }
+ dev->d_sndlen = pstate->png_datlen + 4;
+ uip_icmpsend(dev, &pstate->png_addr);
+ pstate->png_sent = true;
+ return flags;
}
/* Check if the selected timeout has elapsed */
if (ping_timeout(pstate))
{
- /* Yes.. report the timeout */
+ int failcode;
+
+ /* Check if this device is on the same network as the destination
+ * device.
+ */
+
+ if (!uip_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
+ {
+ /* Destination address was not on the local network served by this
+ * device. If a timeout occurs, then the most likely reason is
+ * that the destination address is not reachable.
+ */
+
+ nlldbg("Not reachable\n");
+ failcode = -ENETUNREACH;
+ }
+ else
+ {
+ nlldbg("Ping timeout\n");
+ failcode = -ETIMEDOUT;
+ }
+
+ /* Report the failure */
- nlldbg("Ping timeout\n");
pstate->png_result = failcode;
goto end_wait;
}
/* Continue waiting */
}
+
return flags;
end_wait: